18 #ifndef _ISM_HELPER_H_ 19 #define _ISM_HELPER_H_ 24 #include <asr_msgs/AsrObject.h> 25 #include <asr_object_database/ObjectMetaData.h> 28 #include <ISM/recognizer/Recognizer.hpp> 55 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);
56 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);
108 Eigen::AngleAxisd
calculateTransform(
const Eigen::Vector3d& objectAxis,
const Eigen::Vector3d& referenceAxis,
const Eigen::Vector3d& unitAxis);
ISM::ObjectPtr mRotationRefObject
Current object pose, to which rotation invariant objects are normalized.
virtual ~ObjectConverter()
const bool mIgnoreTypes
Whether to take over object types from AsrObjects.
boost::shared_ptr< ObjectConverter > ObjectConverterPtr
const std::string mRotationObjType
If normalizing to object: Which type of object to normalize to.
const bool mUseConfidenceFromMsg
Whether to take over recognition confidences (into ism rating) from AsrObjects.
const int mEnableRotationMode
Normalize orientations of rotation invariant objects to either a coordinate frame or an not-rotation ...
Eigen::AngleAxisd calculateTransform(const Eigen::Vector3d &objectAxis, const Eigen::Vector3d &referenceAxis, const Eigen::Vector3d &unitAxis)
calculateTransform Caculate the transformation between two vectors.
void normalizeRotationInvariantObjects(ISM::ObjectSetPtr objectSet)
normalizeOrientation Normalizes the orientation of rotation invariance objects accroding to: ...
ros::ServiceClient objectMetaDataClient
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 std::string mRotationFrame
If normalizing to frame: Which frame to normalize to.
const std::string mBaseFrame
Frame to which incoming object messages are transformed.
ros::NodeHandle nodehandle
const int ROTATION_MODE_FRAME
const bool mIgnoreIds
Whether to take over object ids from AsrObjects.
const std::string mRotationObjId
If normalizing to object: Which id of object to normalize to.
const int ROTATION_MODE_OBJECT
const int ROTATION_MODE_DEACTIVATED