#include <ism_helper.h>
Public Member Functions | |
void | normalizeRotationInvariantObjects (ISM::ObjectSetPtr objectSet) |
normalizeOrientation Normalizes the orientation of rotation invariance objects accroding to: More... | |
ObjectConverter (const std::string &pBaseFrame, const bool pIgnoreTypes, const bool pIgnoreIds, const int pEnableRotationMode, const std::string pRotationFrame, const std::string pRotationObjType, const std::string pRotationObjId) | |
ObjectConverter (const std::string &pBaseFrame, const bool pIgnoreTypes, const bool pIgnoreIds, const int pEnableRotationMode, const std::string pRotationFrame, const std::string pRotationObjType, const std::string pRotationObjId, const bool pUseConfidenceFromMsg) | |
virtual | ~ObjectConverter () |
Private Member Functions | |
Eigen::AngleAxisd | calculateTransform (const Eigen::Vector3d &objectAxis, const Eigen::Vector3d &referenceAxis, const Eigen::Vector3d &unitAxis) |
calculateTransform Caculate the transformation between two vectors. More... | |
Private Attributes | |
const std::string | mBaseFrame |
Frame to which incoming object messages are transformed. More... | |
const int | mEnableRotationMode |
Normalize orientations of rotation invariant objects to either a coordinate frame or an not-rotation invariant object. More... | |
const bool | mIgnoreIds |
Whether to take over object ids from AsrObjects. More... | |
const bool | mIgnoreTypes |
Whether to take over object types from AsrObjects. More... | |
const std::string | mRotationFrame |
If normalizing to frame: Which frame to normalize to. More... | |
const std::string | mRotationObjId |
If normalizing to object: Which id of object to normalize to. More... | |
const std::string | mRotationObjType |
If normalizing to object: Which type of object to normalize to. More... | |
ISM::ObjectPtr | mRotationRefObject |
Current object pose, to which rotation invariant objects are normalized. More... | |
const bool | mUseConfidenceFromMsg |
Whether to take over recognition confidences (into ism rating) from AsrObjects. More... | |
ros::NodeHandle | nodehandle |
ros::ServiceClient | objectMetaDataClient |
const int | ROTATION_MODE_DEACTIVATED = 0 |
const int | ROTATION_MODE_FRAME = 1 |
const int | ROTATION_MODE_OBJECT = 2 |
ObjectConverter class. Transforms Asrobjects into ism objects and normalizes orientations of rotation invariant objects.
Definition at line 44 of file ism_helper.h.
IH::ObjectConverter::ObjectConverter | ( | const std::string & | pBaseFrame, |
const bool | pIgnoreTypes, | ||
const bool | pIgnoreIds, | ||
const int | pEnableRotationMode, | ||
const std::string | pRotationFrame, | ||
const std::string | pRotationObjType, | ||
const std::string | pRotationObjId | ||
) |
Constructor setting up transform_listener environment for transforming object messages to world coordinate frame.
pBaseFrame | Frame to which incoming object messages are transformed. |
pIgnoreTypes | Create ism objects that have no type. |
pIgnoreIds | Create ism objects that have no id. |
Copyright (c) 2016, Aumann Florian, Heller Florian, Hutmacher Robin, Meißner Pascal, Stöckle Patrick, Stroh Daniel All rights reserved.
Redistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
Definition at line 27 of file ism_helper.cpp.
IH::ObjectConverter::ObjectConverter | ( | const std::string & | pBaseFrame, |
const bool | pIgnoreTypes, | ||
const bool | pIgnoreIds, | ||
const int | pEnableRotationMode, | ||
const std::string | pRotationFrame, | ||
const std::string | pRotationObjType, | ||
const std::string | pRotationObjId, | ||
const bool | pUseConfidenceFromMsg | ||
) |
Definition at line 34 of file ism_helper.cpp.
|
inlinevirtual |
Definition at line 58 of file ism_helper.h.
|
private |
calculateTransform Caculate the transformation between two vectors.
objectAxis | Object vector. |
referenceAxis | Reference vector. |
Definition at line 93 of file ism_helper.cpp.
void IH::ObjectConverter::normalizeRotationInvariantObjects | ( | ISM::ObjectSetPtr | objectSet | ) |
normalizeOrientation Normalizes the orientation of rotation invariance objects accroding to:
objectSet | accumlated objects to be processed. |
Definition at line 41 of file ism_helper.cpp.
|
private |
Frame to which incoming object messages are transformed.
Definition at line 76 of file ism_helper.h.
|
private |
Normalize orientations of rotation invariant objects to either a coordinate frame or an not-rotation invariant object.
Definition at line 84 of file ism_helper.h.
|
private |
Whether to take over object ids from AsrObjects.
Definition at line 81 of file ism_helper.h.
|
private |
Whether to take over object types from AsrObjects.
Definition at line 79 of file ism_helper.h.
|
private |
If normalizing to frame: Which frame to normalize to.
Definition at line 87 of file ism_helper.h.
|
private |
If normalizing to object: Which id of object to normalize to.
Definition at line 91 of file ism_helper.h.
|
private |
If normalizing to object: Which type of object to normalize to.
Definition at line 89 of file ism_helper.h.
|
private |
Current object pose, to which rotation invariant objects are normalized.
Definition at line 93 of file ism_helper.h.
|
private |
Whether to take over recognition confidences (into ism rating) from AsrObjects.
Definition at line 96 of file ism_helper.h.
|
private |
Definition at line 98 of file ism_helper.h.
|
private |
Definition at line 100 of file ism_helper.h.
|
private |
Definition at line 71 of file ism_helper.h.
|
private |
Definition at line 72 of file ism_helper.h.
|
private |
Definition at line 73 of file ism_helper.h.