ism_helper.h
Go to the documentation of this file.
1 
18 #ifndef _ISM_HELPER_H_
19 #define _ISM_HELPER_H_
20 
21 //Pkg includes
22 #include <ros/ros.h>
23 
24 #include <asr_msgs/AsrObject.h>
25 #include <asr_object_database/ObjectMetaData.h>
26 
27 //Local includes
28 #include <ISM/recognizer/Recognizer.hpp>
29 
36 namespace IH {
37 
45  {
46  public:
47 
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);
57 
58  virtual ~ObjectConverter() {};
59 
67  void normalizeRotationInvariantObjects(ISM::ObjectSetPtr objectSet);
68 
69  private:
70  //Some consts for orientation normalization.
72  const int ROTATION_MODE_FRAME = 1;
73  const int ROTATION_MODE_OBJECT = 2;
74 
76  const std::string mBaseFrame;
77 
79  const bool mIgnoreTypes;
81  const bool mIgnoreIds;
82 
85 
87  const std::string mRotationFrame;
89  const std::string mRotationObjType;
91  const std::string mRotationObjId;
93  ISM::ObjectPtr mRotationRefObject;
94 
97 
99 
101 
108  Eigen::AngleAxisd calculateTransform(const Eigen::Vector3d& objectAxis, const Eigen::Vector3d& referenceAxis, const Eigen::Vector3d& unitAxis);
109  };
110 
112 
113 }
114 
115 #endif /* _ISM_HELPER_H_ */
ISM::ObjectPtr mRotationRefObject
Current object pose, to which rotation invariant objects are normalized.
Definition: ism_helper.h:93
virtual ~ObjectConverter()
Definition: ism_helper.h:58
const bool mIgnoreTypes
Whether to take over object types from AsrObjects.
Definition: ism_helper.h:79
boost::shared_ptr< ObjectConverter > ObjectConverterPtr
Definition: ism_helper.h:111
const std::string mRotationObjType
If normalizing to object: Which type of object to normalize to.
Definition: ism_helper.h:89
Definition: ism_helper.h:36
const bool mUseConfidenceFromMsg
Whether to take over recognition confidences (into ism rating) from AsrObjects.
Definition: ism_helper.h:96
const int mEnableRotationMode
Normalize orientations of rotation invariant objects to either a coordinate frame or an not-rotation ...
Definition: ism_helper.h:84
Eigen::AngleAxisd calculateTransform(const Eigen::Vector3d &objectAxis, const Eigen::Vector3d &referenceAxis, const Eigen::Vector3d &unitAxis)
calculateTransform Caculate the transformation between two vectors.
Definition: ism_helper.cpp:93
void normalizeRotationInvariantObjects(ISM::ObjectSetPtr objectSet)
normalizeOrientation Normalizes the orientation of rotation invariance objects accroding to: ...
Definition: ism_helper.cpp:41
ros::ServiceClient objectMetaDataClient
Definition: ism_helper.h:100
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)
Definition: ism_helper.cpp:27
const std::string mRotationFrame
If normalizing to frame: Which frame to normalize to.
Definition: ism_helper.h:87
const std::string mBaseFrame
Frame to which incoming object messages are transformed.
Definition: ism_helper.h:76
ros::NodeHandle nodehandle
Definition: ism_helper.h:98
const int ROTATION_MODE_FRAME
Definition: ism_helper.h:72
const bool mIgnoreIds
Whether to take over object ids from AsrObjects.
Definition: ism_helper.h:81
const std::string mRotationObjId
If normalizing to object: Which id of object to normalize to.
Definition: ism_helper.h:91
const int ROTATION_MODE_OBJECT
Definition: ism_helper.h:73
const int ROTATION_MODE_DEACTIVATED
Definition: ism_helper.h:71


asr_recognizer_prediction_ism
Author(s): Aumann Florian, Heller Florian, Hutmacher Robin, Meißner Pascal, Stöckle Patrick, Stroh Daniel
autogenerated on Wed Jan 8 2020 03:18:32