void init() { if (types_slam3d::initialized) return; Factory* factory = Factory::instance(); //std::cerr << "Calling " << __FILE__ << " " << __PRETTY_FUNCTION__ << std::endl; factory->registerType("VERTEX_SE3:QUAT", new HyperGraphElementCreator<VertexSE3>); factory->registerType("EDGE_SE3:QUAT", new HyperGraphElementCreator<EdgeSE3>); factory->registerType("VERTEX_TRACKXYZ", new HyperGraphElementCreator<VertexPointXYZ>); factory->registerType("PARAMS_SE3OFFSET", new HyperGraphElementCreator<ParameterSE3Offset>); factory->registerType("EDGE_SE3_TRACKXYZ", new HyperGraphElementCreator<EdgeSE3PointXYZ>); factory->registerType("EDGE_SE3_PRIOR", new HyperGraphElementCreator<EdgeSE3Prior>); factory->registerType("CACHE_SE3_OFFSET", new HyperGraphElementCreator<CacheSE3Offset>); factory->registerType("EDGE_SE3_OFFSET", new HyperGraphElementCreator<EdgeSE3Offset>); factory->registerType("PARAMS_CAMERACALIB", new HyperGraphElementCreator<ParameterCamera>); factory->registerType("CACHE_CAMERA", new HyperGraphElementCreator<CacheCamera>); factory->registerType("EDGE_PROJECT_DISPARITY", new HyperGraphElementCreator<EdgeSE3PointXYZDisparity>); factory->registerType("EDGE_PROJECT_DEPTH", new HyperGraphElementCreator<EdgeSE3PointXYZDepth>); HyperGraphActionLibrary* actionLib = HyperGraphActionLibrary::instance(); actionLib->registerAction(new VertexSE3WriteGnuplotAction); actionLib->registerAction(new EdgeSE3WriteGnuplotAction); #ifdef G2O_HAVE_OPENGL actionLib->registerAction(new VertexPointXYZDrawAction); actionLib->registerAction(new VertexSE3DrawAction); actionLib->registerAction(new EdgeSE3DrawAction); actionLib->registerAction(new CacheCameraDrawAction); #endif types_slam3d::initialized = 1; }
void G2O_ATTRIBUTE_CONSTRUCTOR init_types_slam2d(void) { Factory* factory = Factory::instance(); //cerr << "Calling " << __FILE__ << " " << __PRETTY_FUNCTION__ << endl; factory->registerType("VERTEX_SE2", new HyperGraphElementCreator<VertexSE2>); factory->registerType("VERTEX_XY", new HyperGraphElementCreator<VertexPointXY>); factory->registerType("EDGE_PIOR_SE2", new HyperGraphElementCreator<EdgeSE2Prior>); factory->registerType("EDGE_SE2", new HyperGraphElementCreator<EdgeSE2>); factory->registerType("EDGE_SE2_XY", new HyperGraphElementCreator<EdgeSE2PointXY>); factory->registerType("EDGE_BEARING_SE2_XY", new HyperGraphElementCreator<EdgeSE2PointXYBearing>); factory->registerType("EDGE_SE2_MULTI", new HyperGraphElementCreator<EdgeSE2Multi>); factory->registerType("EDGE_SE2_XY_CALIB", new HyperGraphElementCreator<EdgeSE2PointXYCalib>); HyperGraphActionLibrary* actionLib = HyperGraphActionLibrary::instance(); actionLib->registerAction(new VertexSE2WriteGnuplotAction); actionLib->registerAction(new VertexPointXYWriteGnuplotAction); actionLib->registerAction(new EdgeSE2WriteGnuplotAction); actionLib->registerAction(new EdgeSE2PointXYWriteGnuplotAction); actionLib->registerAction(new EdgeSE2PointXYBearingWriteGnuplotAction); #ifdef G2O_HAVE_OPENGL actionLib->registerAction(new VertexSE2DrawAction); actionLib->registerAction(new VertexPointXYDrawAction); actionLib->registerAction(new EdgeSE2DrawAction); actionLib->registerAction(new EdgeSE2PointXYDrawAction); actionLib->registerAction(new EdgeSE2PointXYBearingDrawAction); #endif }