ObjectDefinitions.h
Go to the documentation of this file.
00001 // ****************************************************************************
00002 // This file is part of the Integrating Vision Toolkit (IVT).
00003 //
00004 // The IVT is maintained by the Karlsruhe Institute of Technology (KIT)
00005 // (www.kit.edu) in cooperation with the company Keyetech (www.keyetech.de).
00006 //
00007 // Copyright (C) 2014 Karlsruhe Institute of Technology (KIT).
00008 // All rights reserved.
00009 //
00010 // Redistribution and use in source and binary forms, with or without
00011 // modification, are permitted provided that the following conditions are met:
00012 //
00013 // 1. Redistributions of source code must retain the above copyright
00014 //    notice, this list of conditions and the following disclaimer.
00015 //
00016 // 2. Redistributions in binary form must reproduce the above copyright
00017 //    notice, this list of conditions and the following disclaimer in the
00018 //    documentation and/or other materials provided with the distribution.
00019 //
00020 // 3. Neither the name of the KIT nor the names of its contributors may be
00021 //    used to endorse or promote products derived from this software
00022 //    without specific prior written permission.
00023 //
00024 // THIS SOFTWARE IS PROVIDED BY THE KIT AND CONTRIBUTORS “AS IS” AND ANY
00025 // EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00026 // WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00027 // DISCLAIMED. IN NO EVENT SHALL THE KIT OR CONTRIBUTORS BE LIABLE FOR ANY
00028 // DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00029 // (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00030 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00031 // ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00032 // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF
00033 // THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00034 // ****************************************************************************
00035 // ****************************************************************************
00036 // Filename:  ObjectDefinitions.h
00037 // Author:    Pedram Azad
00038 // Date:      2005
00039 // ****************************************************************************
00040 
00041 
00042 #ifndef _OBJECT_DEFINITIONS_H_
00043 #define _OBJECT_DEFINITIONS_H_
00044 
00045 
00046 // ****************************************************************************
00047 // Necessary includes
00048 // ****************************************************************************
00049 
00050 #include "DataStructures/DynamicArrayTemplate.h"
00051 #include "Structs/Structs.h"
00052 #include "Math/Math3d.h"
00053 
00054 #include <string>
00055 
00056 
00057 
00058 // ****************************************************************************
00059 // Enums
00060 // ****************************************************************************
00061 
00062 enum ObjectColor
00063 {
00064     eNone,
00065     eBlue,
00066     eBlue2,
00067     eBlue3,
00068     eColored,
00069     eGreen,
00070     eGreen2,
00071     eGreen3,
00072         eOrange,
00073         eOrange2,
00074         eOrange3,
00075         eRed,
00076         eRed2,
00077     eRed3,
00078         eSkin,
00079     eWhite,
00080     eYellow,
00081     eYellow2,
00082     eYellow3,
00083     eNumberOfColors
00084 };
00085 
00086 enum ObjectType
00087 {
00088         eCompactObject,
00089         eTexturedObject,
00090         eHead,
00091         eLeftHand,
00092         eRightHand,
00093         eUnknownObject
00094 };
00095 
00096 
00097 // ****************************************************************************
00098 // Structs
00099 // ****************************************************************************
00100 
00101 struct Object2DEntry
00102 {
00103         Object2DEntry()
00104         {
00105                 id = -1;
00106                 type = eUnknownObject;
00107                 color = eNone;
00108                 data = 0;
00109                 reserved = 0;
00110         }
00111 
00112         Object2DEntry(const Object2DEntry &entry)
00113         {
00114                 id = entry.id;
00115                 region = entry.region;
00116                 type = entry.type;
00117                 color = entry.color;
00118                 sName = "";
00119                 sName += entry.sName;
00120                 data = entry.data;
00121                 reserved = entry.reserved;
00122         }
00123 
00124         int id; // unique id
00125         MyRegion region;
00126         ObjectType type;
00127         ObjectColor color;
00128         std::string sName;
00129         void *data;
00130         int reserved;
00131 };
00132 
00133 struct  Object3DEntry
00134 {
00135     Object3DEntry()
00136         {
00137                 region_id_left = -1;
00138                 region_id_right = -1;
00139                 type = eUnknownObject;
00140                 color = eNone;
00141                 data = 0;
00142                 class_id = -1;
00143                 quality = 0.0f;
00144                 quality2 = 0.0f;
00145         localizationValid = false;
00146         
00147                 Math3d::SetVec(world_point, Math3d::zero_vec);
00148                 Math3d::SetVec(orientation, Math3d::zero_vec);
00149                 Math3d::SetVec(pose.translation, Math3d::zero_vec);
00150                 Math3d::SetMat(pose.rotation, Math3d::unit_mat);
00151         }
00152         
00153         Object3DEntry(const Object3DEntry &entry)
00154         {
00155                 region_left = entry.region_left;
00156                 region_right = entry.region_right;
00157                 region_id_left = entry.region_id_left;
00158                 region_id_right = entry.region_id_right;
00159                 type = entry.type;
00160                 color = entry.color;
00161                 Math3d::SetTransformation(pose, entry.pose);
00162                 Math3d::SetVec(world_point, entry.world_point);
00163                 Math3d::SetVec(orientation, entry.orientation);
00164                 sName = "";
00165                 sName += entry.sName;
00166                 sOivFilePath = "";
00167                 sOivFilePath += entry.sOivFilePath;
00168                 data = entry.data;
00169                 class_id = entry.class_id;
00170                 quality = entry.quality;
00171                 quality2 = entry.quality2;
00172         localizationValid = entry.localizationValid;
00173         }
00174         
00175         MyRegion region_left, region_right;
00176         int region_id_left, region_id_right;
00177         ObjectType type;
00178         ObjectColor color;
00179         Transformation3d pose;
00180         Vec3d world_point;
00181         Vec3d orientation;
00182         std::string sName;
00183         std::string sOivFilePath;
00184         void *data;
00185         int class_id;
00186         float quality, quality2;
00187     bool localizationValid;
00188 };
00189 
00190 // ****************************************************************************
00191 // Typedefs
00192 // ****************************************************************************
00193 
00194 typedef std::vector<Object2DEntry> Object2DList;
00195 typedef std::vector<Object3DEntry> Object3DList;
00196 typedef CDynamicArrayTemplate<Object2DEntry> CObject2DArray;
00197 typedef CDynamicArrayTemplate<Object3DEntry> CObject3DArray;
00198 
00199 
00200 
00201 #endif /* _OBJECT_DEFINITIONS_H_ */


asr_ivt
Author(s): Allgeyer Tobias, Hutmacher Robin, Kleinert Daniel, Meißner Pascal, Scholz Jonas, Stöckle Patrick
autogenerated on Thu Jun 6 2019 21:46:57