#include <RotationInvariantObjectsRotator.hpp>
|
void | rotateRotationInvariantObjects (const std::string &sourceFile, const std::string &targetFile, const std::string &objectType, const std::string &objectId, bool useMapFrame, const std::vector< std::string > &rotationInvariantTypes) |
|
|
Eigen::AngleAxisd | calculateTransform (const Eigen::Vector3d &objectAxis, const Eigen::Vector3d &referenceAxis, const Eigen::Vector3d &unitAxis) |
| calculateTransform Calculate transform between two axis More...
|
|
ObjectPtr | getReferenceObject (ObjectSetPtr oset, const std::string &type, const std::string &id) |
| getReferenceObject Search for reference object in a set More...
|
|
void | normalizeRotationInvarienceObjects (ISM::ObjectSetPtr objectSet, Eigen::Quaterniond quat, const std::vector< std::string > &rotationInvariantTypes) |
| normalizeRotationInvarienceObjects Rotate CS of rotation invariant objects in an object set, so that an object has a fixed orientation to quat. More...
|
|
Represent a tool to merge multiple source databases into one target database.
Definition at line 33 of file RotationInvariantObjectsRotator.hpp.
Eigen::AngleAxisd ISM::RotationInvariantObjectsRotator::calculateTransform |
( |
const Eigen::Vector3d & |
objectAxis, |
|
|
const Eigen::Vector3d & |
referenceAxis, |
|
|
const Eigen::Vector3d & |
unitAxis |
|
) |
| |
|
private |
calculateTransform Calculate transform between two axis
- Parameters
-
objectAxis | oa |
referenceAxis | ra |
unitAxis | to rotate around, if angle is 0 or 180 degrees |
- Returns
- Calculated transform
Definition at line 64 of file RotationInvariantObjectsRotator.cpp.
ObjectPtr ISM::RotationInvariantObjectsRotator::getReferenceObject |
( |
ObjectSetPtr |
oset, |
|
|
const std::string & |
type, |
|
|
const std::string & |
id |
|
) |
| |
|
private |
getReferenceObject Search for reference object in a set
- Parameters
-
oset | object set |
type | type of reference object |
id | ID of reference object |
- Returns
- reference object or nullptr if not found
Definition at line 108 of file RotationInvariantObjectsRotator.cpp.
void ISM::RotationInvariantObjectsRotator::normalizeRotationInvarienceObjects |
( |
ISM::ObjectSetPtr |
objectSet, |
|
|
Eigen::Quaterniond |
quat, |
|
|
const std::vector< std::string > & |
rotationInvariantTypes |
|
) |
| |
|
private |
normalizeRotationInvarienceObjects Rotate CS of rotation invariant objects in an object set, so that an object has a fixed orientation to quat.
- Parameters
-
objectSet | Object set to be processed. |
quat | Orientation reference |
Definition at line 84 of file RotationInvariantObjectsRotator.cpp.
void ISM::RotationInvariantObjectsRotator::rotateRotationInvariantObjects |
( |
const std::string & |
sourceFile, |
|
|
const std::string & |
targetFile, |
|
|
const std::string & |
objectType, |
|
|
const std::string & |
objectId, |
|
|
bool |
useMapFrame, |
|
|
const std::vector< std::string > & |
rotationInvariantTypes |
|
) |
| |
The documentation for this class was generated from the following files:
asr_lib_ism
Author(s): Hanselmann Fabian, Heller Florian, Heizmann Heinrich, Kübler Marcel, Mehlhaus Jonas, Meißner Pascal, Qattan Mohamad, Reckling Reno, Stroh Daniel
autogenerated on Wed Jan 8 2020 04:02:41