$search
#include <rtcMesh3D.h>
Public Member Functions | |
Face3D * | addFace (int vhandles[3]) |
Face3D * | addFace (int v0, int v1, int v2) |
Face3D * | addFace (Face3D *face) |
Vertex3D * | addVertex (const Point3Df &p) |
Vertex3D * | addVertex (Vertex3D *vertex) |
void | clear () |
bool | getFlag (int flag) const |
bool | hasCameraInfo () const |
bool | hasFaceColors () const |
bool | hasFaceFlags () const |
bool | hasFaceNormals () const |
bool | hasFrameID () const |
bool | hasImagePose () const |
bool | hasTexture () const |
bool | hasVertexColors () const |
bool | hasVertexFlags () const |
bool | hasVertexNormals () const |
void | loadTexture () |
Mesh3D (const Mesh3D &other) | |
Mesh3D () | |
int | numFaces () const |
int | numVertices () const |
const Mesh3D & | operator= (const Mesh3D &other) |
void | read (FILE *fp) |
virtual bool | read (InputHandler &ih) |
read IOObject from InputHandler | |
void | set (const Mesh3D &other) |
void | setFlag (int flag, bool value) |
void | unloadTexture () |
void | update () |
void | updateFaces () |
void | updateNormals () |
void | updateVertices () |
void | write (FILE *fp) const |
virtual bool | write (OutputHandler &oh) const |
write IOObject to OutputHandler | |
virtual | ~Mesh3D () |
Public Attributes | |
sensor_msgs::CameraInfo | camera_info |
VecFace3D | faces |
int | flags |
std::string | frame_id |
Pose3Df | image_pose |
Pose3Df | pose |
Image< Vec3uc > | teximage |
Array2i | texmask |
Texture | texture |
VecVertex3D | vertices |
Definition at line 54 of file rtcMesh3D.h.
rtc::Mesh3D::Mesh3D | ( | ) |
Definition at line 29 of file rtcMesh3D.cpp.
rtc::Mesh3D::~Mesh3D | ( | ) | [virtual] |
Definition at line 42 of file rtcMesh3D.cpp.
rtc::Mesh3D::Mesh3D | ( | const Mesh3D & | other | ) |
Definition at line 47 of file rtcMesh3D.cpp.
Face3D * rtc::Mesh3D::addFace | ( | int | vhandles[3] | ) |
Definition at line 178 of file rtcMesh3D.cpp.
Face3D * rtc::Mesh3D::addFace | ( | int | v0, | |
int | v1, | |||
int | v2 | |||
) |
Definition at line 165 of file rtcMesh3D.cpp.
Definition at line 159 of file rtcMesh3D.cpp.
Definition at line 142 of file rtcMesh3D.cpp.
Definition at line 135 of file rtcMesh3D.cpp.
void rtc::Mesh3D::clear | ( | ) |
Definition at line 54 of file rtcMesh3D.cpp.
bool rtc::Mesh3D::getFlag | ( | int | flag | ) | const |
Definition at line 234 of file rtcMesh3D.cpp.
bool rtc::Mesh3D::hasCameraInfo | ( | ) | const |
Definition at line 224 of file rtcMesh3D.cpp.
bool rtc::Mesh3D::hasFaceColors | ( | ) | const |
Definition at line 199 of file rtcMesh3D.cpp.
bool rtc::Mesh3D::hasFaceFlags | ( | ) | const |
Definition at line 209 of file rtcMesh3D.cpp.
bool rtc::Mesh3D::hasFaceNormals | ( | ) | const |
Definition at line 189 of file rtcMesh3D.cpp.
bool rtc::Mesh3D::hasFrameID | ( | ) | const |
Definition at line 229 of file rtcMesh3D.cpp.
bool rtc::Mesh3D::hasImagePose | ( | ) | const |
Definition at line 219 of file rtcMesh3D.cpp.
bool rtc::Mesh3D::hasTexture | ( | ) | const |
Definition at line 214 of file rtcMesh3D.cpp.
bool rtc::Mesh3D::hasVertexColors | ( | ) | const |
Definition at line 194 of file rtcMesh3D.cpp.
bool rtc::Mesh3D::hasVertexFlags | ( | ) | const |
Definition at line 204 of file rtcMesh3D.cpp.
bool rtc::Mesh3D::hasVertexNormals | ( | ) | const |
Definition at line 184 of file rtcMesh3D.cpp.
void rtc::Mesh3D::loadTexture | ( | ) |
Definition at line 429 of file rtcMesh3D.cpp.
int rtc::Mesh3D::numFaces | ( | ) | const |
Definition at line 148 of file rtcMesh3D.cpp.
int rtc::Mesh3D::numVertices | ( | ) | const |
Definition at line 124 of file rtcMesh3D.cpp.
Definition at line 69 of file rtcMesh3D.cpp.
void rtc::Mesh3D::read | ( | FILE * | fp | ) |
Definition at line 513 of file rtcMesh3D.cpp.
bool rtc::Mesh3D::read | ( | InputHandler & | ih | ) | [virtual] |
read IOObject from InputHandler
Implements rtc::IOObject.
Definition at line 325 of file rtcMesh3D.cpp.
void rtc::Mesh3D::set | ( | const Mesh3D & | other | ) |
Definition at line 76 of file rtcMesh3D.cpp.
void rtc::Mesh3D::setFlag | ( | int | flag, | |
bool | value | |||
) |
Definition at line 239 of file rtcMesh3D.cpp.
void rtc::Mesh3D::unloadTexture | ( | ) |
Definition at line 436 of file rtcMesh3D.cpp.
void rtc::Mesh3D::update | ( | ) |
Definition at line 112 of file rtcMesh3D.cpp.
void rtc::Mesh3D::updateFaces | ( | ) |
Definition at line 153 of file rtcMesh3D.cpp.
void rtc::Mesh3D::updateNormals | ( | ) |
Definition at line 116 of file rtcMesh3D.cpp.
void rtc::Mesh3D::updateVertices | ( | ) |
Definition at line 129 of file rtcMesh3D.cpp.
void rtc::Mesh3D::write | ( | FILE * | fp | ) | const |
Definition at line 443 of file rtcMesh3D.cpp.
bool rtc::Mesh3D::write | ( | OutputHandler & | oh | ) | const [virtual] |
write IOObject to OutputHandler
Implements rtc::IOObject.
Definition at line 247 of file rtcMesh3D.cpp.
Definition at line 123 of file rtcMesh3D.h.
Definition at line 114 of file rtcMesh3D.h.
Definition at line 112 of file rtcMesh3D.h.
std::string rtc::Mesh3D::frame_id |
Definition at line 124 of file rtcMesh3D.h.
Definition at line 122 of file rtcMesh3D.h.
Definition at line 111 of file rtcMesh3D.h.
Definition at line 120 of file rtcMesh3D.h.
Definition at line 121 of file rtcMesh3D.h.
Definition at line 118 of file rtcMesh3D.h.
Definition at line 113 of file rtcMesh3D.h.