Default module template. More...
#include <ORMatchingModule.h>
Public Member Functions | |
void | addObjectProperties (ObjectProperties *newProperties) |
void | callbackExtractKeyPoints (const or_msgs::ExtractKeyPoints::ConstPtr &msg) |
void | callbackImage (const sensor_msgs::Image::ConstPtr &message) |
void | callbackOrCommand (const or_msgs::OrCommand::ConstPtr &msg) |
ORMatchingModule (ros::NodeHandle *nh, std::string inputTopic) | |
The constructor. | |
void | processImageMessage (const sensor_msgs::Image::ConstPtr &message) |
virtual | ~ORMatchingModule () |
The destructor. | |
Private Types | |
enum | Stage1MatcherT { NearestNeighbor = 1, Flann = 2 } |
enum | Stage2MatcherT { SimpleHoughClustering = 1, HoughClustering = 2 } |
Private Member Functions | |
std::vector< KeyPoint > | getSceneKeyPointsWithinOutline (std::vector< KeyPoint > *sceneKeyPoints, Homography &homography, std::list< KeyPointMatch > &stage3Matches) |
bool | matchObject (std::vector< KeyPoint > *sceneKeyPoints, ObjectProperties &objectProperties, MatchResult &matchResult) |
try to match keypoints to one specific object | |
std::list< KeyPointMatch > | matchStage1 (std::vector< KeyPoint > *sceneKeyPoints, ImagePropertiesCV *objectImageProperties) |
std::list< KeyPointMatch > | matchStage1Flan (ImagePropertiesCV *objectImageProperties) |
std::vector< std::list < KeyPointMatch > > | matchStage2 (std::vector< KeyPoint > *sceneKeyPoints, ImagePropertiesCV *objectImageProperties, std::list< KeyPointMatch > &stage1Matches) |
std::list< KeyPointMatch > | matchStage3 (std::vector< KeyPoint > *sceneKeyPoints, ImagePropertiesCV *objImageProperties, std::vector< std::list< KeyPointMatch > > &stage2Matches, Homography &homography) |
void | processImages (cv::Mat *image, int seqNum, std::vector< Box2D< int > > boundingBoxes=std::vector< Box2D< int > >()) |
extract all keypoints, then do object recognition on all bounding boxes separately | |
void | processKeyPoints (cv::Mat *image, std::vector< KeyPoint > *rawKeyPoints, std::vector< Box2D< int > > boundingBoxes, unsigned seqNum) |
search for objects on all given keypoints | |
void | removeObjectProperties (std::string name) |
void | sendObjectNames () |
Private Attributes | |
std::vector< Box2D< double > > | m_BoundingBoxes |
ros::Publisher | m_DebugImagePublisherColor |
ros::Subscriber | m_ExtractKeyPointsSubscriber |
KeyPointExtractor * | m_Extractor |
FLANNMatcher * | m_FlannMatcher |
int | m_ImageHeight |
int | m_ImagesRequested |
ros::Subscriber | m_ImageSubscriber |
int | m_ImageWidth |
std::deque< ObjectProperties > | m_ObjectList |
ros::Subscriber | m_OrCommandSubscriber |
ros::Publisher | m_ORMatchResultPublisher |
ros::Publisher | m_ORObjectNamesPublisher |
std::list< double > | m_ProcessingTimes |
Stage1MatcherT | m_Stage1Matcher |
Stage2MatcherT | m_Stage2Matcher |
Default module template.
Definition at line 37 of file ORMatchingModule.h.
enum ORMatchingModule::Stage1MatcherT [private] |
Definition at line 57 of file ORMatchingModule.h.
enum ORMatchingModule::Stage2MatcherT [private] |
Definition at line 63 of file ORMatchingModule.h.
ORMatchingModule::ORMatchingModule | ( | ros::NodeHandle * | nh, |
std::string | inputTopic | ||
) |
The constructor.
virtual ORMatchingModule::~ORMatchingModule | ( | ) | [virtual] |
The destructor.
void ORMatchingModule::addObjectProperties | ( | ObjectProperties * | newProperties | ) |
void ORMatchingModule::callbackExtractKeyPoints | ( | const or_msgs::ExtractKeyPoints::ConstPtr & | msg | ) |
void ORMatchingModule::callbackImage | ( | const sensor_msgs::Image::ConstPtr & | message | ) |
void ORMatchingModule::callbackOrCommand | ( | const or_msgs::OrCommand::ConstPtr & | msg | ) |
std::vector<KeyPoint> ORMatchingModule::getSceneKeyPointsWithinOutline | ( | std::vector< KeyPoint > * | sceneKeyPoints, |
Homography & | homography, | ||
std::list< KeyPointMatch > & | stage3Matches | ||
) | [private] |
bool ORMatchingModule::matchObject | ( | std::vector< KeyPoint > * | sceneKeyPoints, |
ObjectProperties & | objectProperties, | ||
MatchResult & | matchResult | ||
) | [private] |
try to match keypoints to one specific object
std::list< KeyPointMatch > ORMatchingModule::matchStage1 | ( | std::vector< KeyPoint > * | sceneKeyPoints, |
ImagePropertiesCV * | objectImageProperties | ||
) | [private] |
std::list< KeyPointMatch > ORMatchingModule::matchStage1Flan | ( | ImagePropertiesCV * | objectImageProperties | ) | [private] |
std::vector< std::list< KeyPointMatch> > ORMatchingModule::matchStage2 | ( | std::vector< KeyPoint > * | sceneKeyPoints, |
ImagePropertiesCV * | objectImageProperties, | ||
std::list< KeyPointMatch > & | stage1Matches | ||
) | [private] |
std::list< KeyPointMatch > ORMatchingModule::matchStage3 | ( | std::vector< KeyPoint > * | sceneKeyPoints, |
ImagePropertiesCV * | objImageProperties, | ||
std::vector< std::list< KeyPointMatch > > & | stage2Matches, | ||
Homography & | homography | ||
) | [private] |
void ORMatchingModule::processImageMessage | ( | const sensor_msgs::Image::ConstPtr & | message | ) |
void ORMatchingModule::processImages | ( | cv::Mat * | image, |
int | seqNum, | ||
std::vector< Box2D< int > > | boundingBoxes = std::vector< Box2D< int > >() |
||
) | [private] |
extract all keypoints, then do object recognition on all bounding boxes separately
boundingBoxes | bounding boxes to use. if empty, the full image is used. |
void ORMatchingModule::processKeyPoints | ( | cv::Mat * | image, |
std::vector< KeyPoint > * | rawKeyPoints, | ||
std::vector< Box2D< int > > | boundingBoxes, | ||
unsigned | seqNum | ||
) | [private] |
search for objects on all given keypoints
void ORMatchingModule::removeObjectProperties | ( | std::string | name | ) | [private] |
void ORMatchingModule::sendObjectNames | ( | ) | [private] |
std::vector< Box2D<double> > ORMatchingModule::m_BoundingBoxes [private] |
Definition at line 103 of file ORMatchingModule.h.
Definition at line 123 of file ORMatchingModule.h.
Definition at line 118 of file ORMatchingModule.h.
KeyPointExtractor* ORMatchingModule::m_Extractor [private] |
Definition at line 111 of file ORMatchingModule.h.
FLANNMatcher* ORMatchingModule::m_FlannMatcher [private] |
Definition at line 115 of file ORMatchingModule.h.
int ORMatchingModule::m_ImageHeight [private] |
Definition at line 109 of file ORMatchingModule.h.
int ORMatchingModule::m_ImagesRequested [private] |
Definition at line 102 of file ORMatchingModule.h.
Definition at line 119 of file ORMatchingModule.h.
int ORMatchingModule::m_ImageWidth [private] |
Definition at line 108 of file ORMatchingModule.h.
std::deque<ObjectProperties> ORMatchingModule::m_ObjectList [private] |
Definition at line 100 of file ORMatchingModule.h.
Definition at line 117 of file ORMatchingModule.h.
Definition at line 121 of file ORMatchingModule.h.
Definition at line 122 of file ORMatchingModule.h.
std::list<double> ORMatchingModule::m_ProcessingTimes [private] |
Definition at line 113 of file ORMatchingModule.h.
Definition at line 105 of file ORMatchingModule.h.
Definition at line 106 of file ORMatchingModule.h.