Public Member Functions | Private Member Functions | Private Attributes | List of all members
IH::ObjectConverter Class Reference

#include <ism_helper.hpp>

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)
 
ISM::ObjectPtr pbdObjectToISMObject (const asr_msgs::AsrObject &o)
 
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...
 
tf::TransformListener mTfListener
 Needed for transform to base_frame coordinate system. 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
 
std::vector< asr_msgs::AsrObject > transformBuffer
 Needed to store poses which have not yet been transformed. More...
 

Detailed Description

Namespace ism helper. Some functions needed in ros nodes interfacing libism.

Author
Pascal Meissner
Version
See SVN

Definition at line 53 of file ism_helper.hpp.

Constructor & Destructor Documentation

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.

Parameters
pBaseFrameFrame to which incoming object messages are transformed.
pIgnoreTypesCreate ism objects that have no type.
pIgnoreIdsCreate ism objects that have no id.

Copyright (c) 2016, Borella Jocelyn, Hanselmann Fabian, Heller Florian, Heizmann Heinrich, Kübler Marcel, Mehlhaus Jonas, Meißner Pascal, Qattan Mohamad, Reckling Reno, 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:

  1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer.
  2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution.
  3. Neither the name of the copyright holder nor the names of its contributors may be used to endorse or promote products derived from this software without specific prior written permission.

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 32 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 41 of file ism_helper.cpp.

virtual IH::ObjectConverter::~ObjectConverter ( )
inlinevirtual

Definition at line 67 of file ism_helper.hpp.

Member Function Documentation

Eigen::AngleAxisd IH::ObjectConverter::calculateTransform ( const Eigen::Vector3d &  objectAxis,
const Eigen::Vector3d &  referenceAxis,
const Eigen::Vector3d &  unitAxis 
)
private

calculateTransform Caculate the transformation between two vectors.

Parameters
objectAxisObject vector.
referenceAxisReference vector.
Returns

Definition at line 136 of file ism_helper.cpp.

void IH::ObjectConverter::normalizeRotationInvariantObjects ( ISM::ObjectSetPtr  objectSet)

normalizeOrientation Normalizes the orientation of rotation invariance objects accroding to:

  • RotationFrame
  • or rotationObject params in capturing.yaml.
    Parameters
    objectSetaccumlated objects to be processed.

Definition at line 84 of file ism_helper.cpp.

ISM::ObjectPtr IH::ObjectConverter::pbdObjectToISMObject ( const asr_msgs::AsrObject &  o)

Extract class and identifier (within class) from estimation given by object localization system. Object 7D pose is extracted as well and transformed into world coordinate frame fixed during app startup.

Parameters
oROS object msgs from which information is extracted.
Returns
ISM representation of class, id and pose being extracted.

Definition at line 59 of file ism_helper.cpp.

Member Data Documentation

const std::string IH::ObjectConverter::mBaseFrame
private

Frame to which incoming object messages are transformed.

Definition at line 95 of file ism_helper.hpp.

const int IH::ObjectConverter::mEnableRotationMode
private

Normalize orientations of rotation invariant objects to either a coordinate frame or an not-rotation invariant object.

Definition at line 103 of file ism_helper.hpp.

const bool IH::ObjectConverter::mIgnoreIds
private

Whether to take over object ids from AsrObjects.

Definition at line 100 of file ism_helper.hpp.

const bool IH::ObjectConverter::mIgnoreTypes
private

Whether to take over object types from AsrObjects.

Definition at line 98 of file ism_helper.hpp.

const std::string IH::ObjectConverter::mRotationFrame
private

If normalizing to frame: Which frame to normalize to.

Definition at line 106 of file ism_helper.hpp.

const std::string IH::ObjectConverter::mRotationObjId
private

If normalizing to object: Which id of object to normalize to.

Definition at line 110 of file ism_helper.hpp.

const std::string IH::ObjectConverter::mRotationObjType
private

If normalizing to object: Which type of object to normalize to.

Definition at line 108 of file ism_helper.hpp.

ISM::ObjectPtr IH::ObjectConverter::mRotationRefObject
private

Current object pose, to which rotation invariant objects are normalized.

Definition at line 112 of file ism_helper.hpp.

tf::TransformListener IH::ObjectConverter::mTfListener
private

Needed for transform to base_frame coordinate system.

Definition at line 92 of file ism_helper.hpp.

const bool IH::ObjectConverter::mUseConfidenceFromMsg
private

Whether to take over recognition confidences (into ism rating) from AsrObjects.

Definition at line 115 of file ism_helper.hpp.

ros::NodeHandle IH::ObjectConverter::nodehandle
private

Definition at line 120 of file ism_helper.hpp.

ros::ServiceClient IH::ObjectConverter::objectMetaDataClient
private

Definition at line 122 of file ism_helper.hpp.

const int IH::ObjectConverter::ROTATION_MODE_DEACTIVATED = 0
private

Definition at line 87 of file ism_helper.hpp.

const int IH::ObjectConverter::ROTATION_MODE_FRAME = 1
private

Definition at line 88 of file ism_helper.hpp.

const int IH::ObjectConverter::ROTATION_MODE_OBJECT = 2
private

Definition at line 89 of file ism_helper.hpp.

std::vector<asr_msgs::AsrObject> IH::ObjectConverter::transformBuffer
private

Needed to store poses which have not yet been transformed.

Definition at line 118 of file ism_helper.hpp.


The documentation for this class was generated from the following files:


asr_ism
Author(s): Borella Jocelyn, Hanselmann Fabian, Heller Florian, Heizmann Heinrich, Kübler Marcel, Mehlhaus Jonas, Meißner Pascal, Qattan Mohamad, Reckling Reno, Stroh Daniel
autogenerated on Thu Jan 9 2020 07:20:58