Graph.h
Go to the documentation of this file.
00001 /*
00002 Copyright (c) 2010-2016, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
00003 All rights reserved.
00004 
00005 Redistribution and use in source and binary forms, with or without
00006 modification, are permitted provided that the following conditions are met:
00007     * Redistributions of source code must retain the above copyright
00008       notice, this list of conditions and the following disclaimer.
00009     * Redistributions in binary form must reproduce the above copyright
00010       notice, this list of conditions and the following disclaimer in the
00011       documentation and/or other materials provided with the distribution.
00012     * Neither the name of the Universite de Sherbrooke nor the
00013       names of its contributors may be used to endorse or promote products
00014       derived from this software without specific prior written permission.
00015 
00016 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
00017 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00018 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00019 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
00020 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00021 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00022 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00023 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00024 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00025 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00026 */
00027 
00028 #ifndef GRAPH_H_
00029 #define GRAPH_H_
00030 
00031 #include "rtabmap/core/RtabmapExp.h" // DLL export/import defines
00032 
00033 #include <map>
00034 #include <list>
00035 #include <rtabmap/core/Link.h>
00036 
00037 namespace rtabmap {
00038 class Memory;
00039 
00040 namespace graph {
00041 
00043 // Graph utilities
00045 
00046 bool RTABMAP_EXP exportPoses(
00047                 const std::string & filePath,
00048                 int format, // 0=Raw (*.txt), 1=RGBD-SLAM (*.txt), 2=KITTI (*.txt), 3=TORO (*.graph), 4=g2o (*.g2o)
00049                 const std::map<int, Transform> & poses,
00050                 const std::multimap<int, Link> & constraints = std::multimap<int, Link>(), // required for formats 3 and 4
00051                 const std::map<int, double> & stamps = std::map<int, double>(),  // required for format 1
00052                 bool g2oRobust = false); // optional for format 4
00053 
00054 bool RTABMAP_EXP importPoses(
00055                 const std::string & filePath,
00056                 int format, // 0=Raw, 1=RGBD-SLAM, 2=KITTI, 3=TORO, 4=g2o, GPS (t,x,y)
00057                 std::map<int, Transform> & poses,
00058                 std::multimap<int, Link> * constraints = 0, // optional for formats 3 and 4
00059                 std::map<int, double> * stamps = 0); // optional for format 1
00060 
00061 std::multimap<int, Link>::iterator RTABMAP_EXP findLink(
00062                 std::multimap<int, Link> & links,
00063                 int from,
00064                 int to,
00065                 bool checkBothWays = true);
00066 std::multimap<int, int>::iterator RTABMAP_EXP findLink(
00067                 std::multimap<int, int> & links,
00068                 int from,
00069                 int to,
00070                 bool checkBothWays = true);
00071 std::multimap<int, Link>::const_iterator RTABMAP_EXP findLink(
00072                 const std::multimap<int, Link> & links,
00073                 int from,
00074                 int to,
00075                 bool checkBothWays = true);
00076 std::multimap<int, int>::const_iterator RTABMAP_EXP findLink(
00077                 const std::multimap<int, int> & links,
00078                 int from,
00079                 int to,
00080                 bool checkBothWays = true);
00081 
00082 std::multimap<int, Link> RTABMAP_EXP filterLinks(
00083                 const std::multimap<int, Link> & links,
00084                 Link::Type filteredType);
00085 std::map<int, Link> RTABMAP_EXP filterLinks(
00086                 const std::map<int, Link> & links,
00087                 Link::Type filteredType);
00088 
00089 //Note: This assumes a coordinate system where X is forward, * Y is up, and Z is right.
00090 std::map<int, Transform> RTABMAP_EXP frustumPosesFiltering(
00091                 const std::map<int, Transform> & poses,
00092                 const Transform & cameraPose,
00093                 float horizontalFOV = 45.0f, // in degrees, xfov = atan((image_width/2)/fx)*2
00094                 float verticalFOV = 45.0f,   // in degrees, yfov = atan((image_height/2)/fy)*2
00095                 float nearClipPlaneDistance = 0.1f,
00096                 float farClipPlaneDistance = 100.0f,
00097                 bool negative = false);
00098 
00107 std::map<int, Transform> RTABMAP_EXP radiusPosesFiltering(
00108                 const std::map<int, Transform> & poses,
00109                 float radius,
00110                 float angle,
00111                 bool keepLatest = true);
00112 
00120 std::multimap<int, int> RTABMAP_EXP radiusPosesClustering(
00121                 const std::map<int, Transform> & poses,
00122                 float radius,
00123                 float angle);
00124 
00125 void reduceGraph(
00126                 const std::map<int, Transform> & poses,
00127                 const std::multimap<int, Link> & links,
00128                 std::multimap<int, int> & hyperNodes, //<parent ID, child ID>
00129                 std::multimap<int, Link> & hyperLinks);
00130 
00140 std::list<std::pair<int, Transform> > RTABMAP_EXP computePath(
00141                         const std::map<int, rtabmap::Transform> & poses,
00142                         const std::multimap<int, int> & links,
00143                         int from,
00144                         int to,
00145                         bool updateNewCosts = false);
00146 
00157 std::list<int> RTABMAP_EXP computePath(
00158                         const std::multimap<int, Link> & links,
00159                         int from,
00160                         int to,
00161                         bool updateNewCosts = false,
00162                         bool useSameCostForAllLinks = false);
00163 
00173 std::list<std::pair<int, Transform> > RTABMAP_EXP computePath(
00174                 int fromId,
00175                 int toId,
00176                 const Memory * memory,
00177                 bool lookInDatabase = true,
00178                 bool updateNewCosts = false,
00179                 float linearVelocity = 0.0f,   // m/sec
00180                 float angularVelocity = 0.0f); // rad/sec
00181 
00182 int RTABMAP_EXP findNearestNode(
00183                 const std::map<int, rtabmap::Transform> & nodes,
00184                 const rtabmap::Transform & targetPose);
00185 
00193 std::map<int, float> RTABMAP_EXP getNodesInRadius(
00194                 int nodeId,
00195                 const std::map<int, Transform> & nodes,
00196                 float radius);
00197 std::map<int, Transform> RTABMAP_EXP getPosesInRadius(
00198                 int nodeId,
00199                 const std::map<int, Transform> & nodes,
00200                 float radius,
00201                 float angle = 0.0f);
00202 
00203 float RTABMAP_EXP computePathLength(
00204                 const std::vector<std::pair<int, Transform> > & path,
00205                 unsigned int fromIndex = 0,
00206                 unsigned int toIndex = 0);
00207 
00208 std::list<std::map<int, Transform> > RTABMAP_EXP getPaths(
00209                 std::map<int, Transform> poses,
00210                 const std::multimap<int, Link> & links);
00211 
00212 
00213 } /* namespace graph */
00214 
00215 } /* namespace rtabmap */
00216 #endif /* GRAPH_H_ */


rtabmap
Author(s): Mathieu Labbe
autogenerated on Sat Jul 23 2016 11:44:16