Utility functions for working with 3D coordinates. More...
#include "cv.h"
#include "cxcore.h"
#include "highgui.h"
#include <iostream>
Go to the source code of this file.
Classes | |
struct | Utils3D::_PLANE |
struct | Utils3D::_PLANE2 |
struct | Utils3D::_STRAIGHTLINE |
Namespaces | |
namespace | Utils3D |
Typedefs | |
typedef struct Utils3D::_PLANE | Utils3D::PLANE |
typedef struct Utils3D::_PLANE2 | Utils3D::PLANE2 |
typedef struct Utils3D::_STRAIGHTLINE | Utils3D::STRAIGHTLINE |
Functions | |
void | Utils3D::addPoints (CvPoint3D32f *p1, CvPoint3D32f *p2, CvPoint3D32f *res) |
p1 + p2 | |
void | Utils3D::addWPoints (CvPoint3D32f *p1, float w1, CvPoint3D32f *p2, float w2, CvPoint3D32f *np) |
calculate a weighted sum of two 3D Points in place ( w1 * p1 + w2 * p2 ) | |
CvPoint3D32f * | Utils3D::cAddPoints (CvPoint3D32f *p1, CvPoint3D32f *p2) |
create a new 3D Point and store the result of p1 + p2 | |
CvPoint3D32f * | Utils3D::cAddWPoints (CvPoint3D32f *p1, float w1, CvPoint3D32f *p2, float w2) |
create a new 3D Point and calculate a weighted sum of two 3D Points ( w1 * p1 + w2 * p2 ) | |
CvMat * | Utils3D::cCalcRectificationMatrix (CvPoint2D32f *oriP1, CvPoint2D32f *oriP2, CvPoint2D32f *oriP3, CvPoint2D32f *oriP4, CvPoint2D32f *dstP1, CvPoint2D32f *dstP2, CvPoint2D32f *dstP3, CvPoint2D32f *dstP4) |
Calculation of the rectification matrix, input: 4 original points and 4 points, where the original points should be projected to. | |
CvPoint3D32f * | Utils3D::cCopyPoint (CvPoint3D32f *p) |
Create a new 3D Point copy the 3D Point p. | |
CvPoint3D32f * | Utils3D::cCrossProduct (CvPoint3D32f *p1, CvPoint3D32f *p2) |
Creates a new 3D Point and calculates the cross product of p1 X p2. | |
CvMat * | Utils3D::cGetBasisFrom3Points (CvPoint3D32f *p1, CvPoint3D32f *p2, CvPoint3D32f *p3) |
returns a Matrix corresponding to the basis of the three points p1, p2 and p3 | |
CvMat * | Utils3D::cGetBasisFrom3Points3x3 (CvPoint3D32f *p1, CvPoint3D32f *p2, CvPoint3D32f *p3) |
CvMat * | Utils3D::cGetMat32fFrom64d (CvMat *mat64d) |
CvMat * | Utils3D::cGetMat64dFrom32f (CvMat *mat32f) |
CvPoint3D32f * | Utils3D::cGetPoint (float x, float y, float z) |
Create a new 3D Point and initialize with x, y, and z. | |
CvPoint3D32f * | Utils3D::cInverseRectifyPoint (CvPoint3D32f *oriPoint, float sensorLenghtScale, float sensorWidthScale, float sensorHeightScale, CvMat *map_matrix) |
CvMat * | Utils3D::createIdentityMatrix () |
Creates a CvMat Identity-Matrix. | |
CvMat * | Utils3D::createMatrixFrom3Points (CvPoint3D32f *p1, CvPoint3D32f *p2, CvPoint3D32f *p3) |
CvMat * | Utils3D::createRotationCoordinateSystemMatrixX (double angle) |
Creates a CvMat Matrix for Rotation of the Coordinate System in X-Direction. | |
CvMat * | Utils3D::createRotationCoordinateSystemMatrixY (double angle) |
Creates a CvMat Matrix for Rotation of the Coordinate System in Y-Direction. | |
CvMat * | Utils3D::createRotationCoordinateSystemMatrixZ (double angle) |
Creates a CvMat Matrix for Rotation of the Coordinate System in Z-Direction. | |
CvMat * | Utils3D::createRotationMatrixX (double angle) |
Creates a CvMat Matrix for Rotation in X-Direction. | |
CvMat * | Utils3D::createRotationMatrixY (double angle) |
Creates a CvMat Matrix for Rotation in Y-Direction. | |
CvMat * | Utils3D::createRotationMatrixZ (double angle) |
Creates a CvMat Matrix for Rotation in Z-Direction. | |
CvMat * | Utils3D::createTransformationMatrix (CvPoint3D32f *trans, double rotX, double rotY, double rotZ) |
Creates a CvMat Matrix for translation and rotation. | |
CvMat * | Utils3D::createTransformationMatrix (CvPoint3D32f *trans, CvPoint3D32f *rot) |
Creates a CvMat Matrix for translation and rotation. | |
CvMat * | Utils3D::createTranslationMatrix (CvPoint3D32f *trans) |
Creates a CvMat Matrix from a translation Vector. | |
CvPoint3D32f * | Utils3D::cRectifyPoint (CvPoint3D32f *oriPoint, float sensorLenghtScale, float sensorWidthScale, float sensorHeightScale, CvMat *map_matrix) |
Rectification and inverse Rectification of a single point. | |
void | Utils3D::crossProduct (CvPoint3D32f *p1, CvPoint3D32f *p2, CvPoint3D32f *np) |
np = p1 X p2 | |
CvPoint3D32f * | Utils3D::cSubPoints (CvPoint3D32f *p1, CvPoint3D32f *p2) |
Create a new 3D Point and store the result of ( p1 - p2 ) in it. | |
double | Utils3D::distPoints (CvPoint3D32f *p1, CvPoint3D32f *p2) |
double | Utils3D::dotProd (CvPoint3D32f *p1, CvPoint3D32f *p2) |
calculate the dotproduct of two 3D Points | |
void | Utils3D::fillPlane (CvPoint3D32f loc, CvPoint3D32f dir1, CvPoint3D32f dir2, PLANE *plane) |
fill in values in a given PLANE plane | |
void | Utils3D::fillPlane (float locX, float locY, float locZ, float dir1X, float dir1Y, float dir1Z, float dir2X, float dir2Y, float dir2Z, PLANE *plane) |
fill in values in a given PLANE plane | |
void | Utils3D::fillStraightLine (CvPoint3D32f *loc, CvPoint3D32f *dir, STRAIGHTLINE *line) |
fill in values in a given STRAIGHTLINE line | |
void | Utils3D::fillStraightLine (float locX, float locY, float locZ, float dirX, float dirY, float dirZ, STRAIGHTLINE *line) |
fill in values in a given STRAIGHTLINE line | |
void | Utils3D::generatePlaneVectorsFromNormal (CvPoint3D32f *plainNormal, CvPoint3D32f *v1, CvPoint3D32f *v2) |
double | Utils3D::getAngle (CvPoint3D32f *p1, CvPoint3D32f *p2) |
calculate a angle between two 3D points | |
float | Utils3D::getLineParameter (STRAIGHTLINE line, CvPoint3D32f p) |
CvPoint3D32f | Utils3D::getLinePoint (STRAIGHTLINE line, float param) |
double | Utils3D::getNorm (CvPoint3D32f *p) |
returns the length of vector p | |
double | Utils3D::getPointPlaneDistance (PLANE2 P, CvPoint3D32f p) |
float | Utils3D::getShortestDistanceBetweenTwoLines (STRAIGHTLINE line1, STRAIGHTLINE line2, float *d1, float *d2) |
double | Utils3D::intersectLinePlane (STRAIGHTLINE line, PLANE plain) |
double | Utils3D::intersectLinePlane (STRAIGHTLINE line, PLANE2 plane) |
STRAIGHTLINE | Utils3D::intersectPlanes (PLANE2 P1, PLANE2 P2) |
void | Utils3D::normalize (CvPoint3D32f *vec) |
normalizes a Vector | |
void | Utils3D::orthonormalizePoints (CvPoint3D32f *p1, CvPoint3D32f *p2, CvPoint3D32f *p3) |
orthonormalize Points | |
void | Utils3D::orthonormalizePoints (CvPoint3D32f *p1, CvPoint3D32f *p2, CvPoint3D32f *p3, double scale) |
orthonormalize Points and scale them | |
CvPoint3D32f | Utils3D::projectPointOnLine (STRAIGHTLINE line, CvPoint3D32f *p) |
CvPoint3D32f | Utils3D::projectPointOnPlane (PLANE2 P, CvPoint3D32f p) |
void | Utils3D::scalePoint (CvPoint3D32f *p, double scale) |
scale the 3D Point p with factor scale | |
void | Utils3D::setCoords (CvPoint3D32f *in, CvPoint3D32f *out) |
set the values of out to the values of in | |
void | Utils3D::setCoords (CvPoint3D32f *out, float x, float y, float z) |
set the values of out to x, y and z | |
int | Utils3D::sgn (float in) |
void | Utils3D::subPoints (CvPoint3D32f *p1, CvPoint3D32f *p2, CvPoint3D32f *res) |
res = p1 - p2 | |
void | Utils3D::swapPoints (CvPoint3D32f *p1, CvPoint3D32f *p2) |
swaps two 3D Points | |
void | Utils3D::transformDirection (CvPoint3D32f *dir, CvMat *transformationMat) |
this Function transforms a direction Vector with a transformation Matrix | |
void | Utils3D::transformPlane (PLANE *plane, CvMat *transformationMat) |
this Function transforms a PLANE with a transformation Matrix | |
void | Utils3D::transformPoint (CvPoint3D32f *point, CvMat *transformationMat) |
this Function transforms a Point with a transformation Matrix | |
void | Utils3D::transformStraightLine (STRAIGHTLINE *line, CvMat *transformationMat) |
this Function transforms a STRAIGHTLINE with a transformation Matrix |
Utility functions for working with 3D coordinates.
This file is part of the RoboEarth ROS ar_bounding_box package.
It file was originally created for RoboEarth. The research leading to these results has received funding from the European Union Seventh Framework Programme FP7/2007-2013 under grant agreement no248942 RoboEarth.
Copyright (C) 2011 by Andreas Koch, University of Stuttgart
This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by the Free Software Foundation, either version 3 of the License, or (at your option) any later version.
This program is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for more details.
You should have received a copy of the GNU General Public License along with this program. If not, see <http://www.gnu.org/licenses/>.
Definition in file Utils3D.h.