Public Member Functions | Private Member Functions | Private Attributes
descriptor_surface_based_recognition::DescriptorSurfaceBasedRecognition Class Reference

#include <descriptor_surface_based_recognition.h>

List of all members.

Public Member Functions

 DescriptorSurfaceBasedRecognition ()
 The constructor of this class.

Private Member Functions

void clearMarkers ()
 Clears the visualized markers of the last frame.
void configCallback (DescriptorSurfaceBasedRecognitionConfig &config_, uint32_t level)
 The callback function which is called when the configuration file has changed.
asr_msgs::AsrObjectPtr createAsrMessage (PoseRecognition *pose_rec, int results_index, std_msgs::Header header)
 Creates a Asr-Object-Message containing the results of a found object instance.
void createBoxMarker (RecognitionResult *result, std_msgs::Header header, rgb color, bool drawCompleteBoxes)
 Adds a bounding box marker which indicates the size of the reduced point cloud used to recognize the given object instance to the array of bounding box markers (msgs_box_markerArray)
void createMarker (asr_msgs::AsrObjectPtr &object, std::string &mesh_path)
 Adds a marker which indicates the pose of the found object to the array containing all found markers of this frame (msgs_markerArray)
pcl::PointCloud
< pcl::PointXYZRGB >::Ptr 
createVisualizationCloud (std::vector< PoseRecognition * > &pose_recs, std_msgs::Header header)
 Creates a single, colored point cloud from the reduced point clouds which were used to recognize the found objects.
void initializeMeshes ()
 Loads all available object meshes so they can be used later.
void overlaySceneWith2DResults (PoseRecognition *pose_rec, HalconCpp::HImage *scene_image)
 Paints the results of the 2D recognition (bounding box, feature points & orientation triangle) to the given scene image.
bool processClearAllRecognizersRequest (ClearAllRecognizers::Request &req, ClearAllRecognizers::Response &res)
bool processGetObjectListRequest (GetObjectList::Request &req, GetObjectList::Response &res)
bool processGetRecognizerRequest (GetRecognizer::Request &req, GetRecognizer::Response &res)
bool processReleaseRecognizerRequest (ReleaseRecognizer::Request &req, ReleaseRecognizer::Response &res)
void rosCallback (const sensor_msgs::ImageConstPtr &input_image_guppy, const sensor_msgs::ImageConstPtr &input_image_guppy_mono, const sensor_msgs::PointCloud2ConstPtr &input_point_cloud_with_guppy)
 The callback function for the ros subscriptions (images and point cloud; called for every new frame)
bool startObjectRecognition (std::string name, int count, bool use_pose_val)
 Adds an object to the list of searchable objects.
void stopObjectRecognition (std::string name)
 Removes an object from the list of searchable objects.
void threadTask (PoseRecognition *pose_rec)
 The task given to each thread in the threadpool (=> Search a specific object)

Private Attributes

ros::Publisher boxes_pub_
ros::ServiceServer clear_all_recognizers_service_
ros::Publisher cloud_pub_
DescriptorSurfaceBasedRecognitionConfig config_
int frame_counter_
ros::ServiceServer get_object_list_service_
ros::ServiceServer get_recognizer_service_
std::string image_color_topic_
message_filters::Subscriber
< sensor_msgs::Image > 
image_mono_sub_
std::string image_mono_topic_
ros::Publisher image_pub_
message_filters::Subscriber
< sensor_msgs::Image > 
image_sub_
std::vector< Object2DPositionslast_frame_positions_
ros::Publisher marker_pub_
std::vector< Ogre::MeshPtr > meshes_
visualization_msgs::MarkerArrayPtr msgs_box_marker_array_
visualization_msgs::MarkerArrayPtr msgs_marker_array_
ros::NodeHandle nh_
ros::ServiceClient object_db_meshes_service_client_
ros::ServiceClient object_db_service_client_
std::vector< ObjectDescriptorobjects_
ros::Publisher objects_pub_
std::string output_cloud_topic_
std::string output_image_topic_
std::string output_marker_bounding_box_topic_
std::string output_marker_topic_
std::string output_objects_topic_
std::ofstream outstream_poses_
std::ofstream outstream_times_
message_filters::Subscriber
< sensor_msgs::PointCloud2 > 
pc_with_guppy_sub_
std::string point_cloud_topic_
PoseValidation pose_val_
dynamic_reconfigure::Server
< DescriptorSurfaceBasedRecognitionConfig > 
reconfigure_server_
ros::ServiceServer release_recognizer_service_
boost::shared_ptr
< ApproximateSync
sync_policy_
boost::threadpool::pool thread_pool_

Detailed Description

The central class of the recognition system used for managing the ros subscriptions, configuration changes, loading of the objects, the search tasks and the visualisation of the results

Definition at line 90 of file descriptor_surface_based_recognition.h.


Constructor & Destructor Documentation

The constructor of this class.

Definition at line 59 of file descriptor_surface_based_recognition.cpp.


Member Function Documentation

Clears the visualized markers of the last frame.

Definition at line 581 of file descriptor_surface_based_recognition.cpp.

void descriptor_surface_based_recognition::DescriptorSurfaceBasedRecognition::configCallback ( DescriptorSurfaceBasedRecognitionConfig &  config_,
uint32_t  level 
) [private]

The callback function which is called when the configuration file has changed.

Parameters:
configThe updated configuration
levelThe level which is the result of ORing together all of level values of the parameters that have changed

Definition at line 481 of file descriptor_surface_based_recognition.cpp.

asr_msgs::AsrObjectPtr descriptor_surface_based_recognition::DescriptorSurfaceBasedRecognition::createAsrMessage ( PoseRecognition pose_rec,
int  results_index,
std_msgs::Header  header 
) [private]

Creates a Asr-Object-Message containing the results of a found object instance.

Parameters:
pose_recA pointer to the recognition class containing the results for a specific object
results_indexThe index of the found instance of the given object class (in pose_rec)
headerContains information about the frame the found pose is relative to
Returns:
The Asr-Object-Message containing meta-data of the found object instance and its recognition results (e.g. its pose)

Definition at line 493 of file descriptor_surface_based_recognition.cpp.

Adds a bounding box marker which indicates the size of the reduced point cloud used to recognize the given object instance to the array of bounding box markers (msgs_box_markerArray)

Parameters:
resultThe result of the object recognition (contains information about one specific found object instance)
headerContains information about the frame the found pose is relative to
colorThe (rgb-) color of the bounding box
drawCompleteBoxesIf false only the side of the box which faces the camera is drawn, the complete box otherwise

Definition at line 596 of file descriptor_surface_based_recognition.cpp.

void descriptor_surface_based_recognition::DescriptorSurfaceBasedRecognition::createMarker ( asr_msgs::AsrObjectPtr &  object,
std::string &  mesh_path 
) [private]

Adds a marker which indicates the pose of the found object to the array containing all found markers of this frame (msgs_markerArray)

Parameters:
objectThe found object instance containing the pose and frame information
mesh_pathPath to the (visualisation-) mesh of the given object instance

Definition at line 552 of file descriptor_surface_based_recognition.cpp.

Creates a single, colored point cloud from the reduced point clouds which were used to recognize the found objects.

Parameters:
pose_recsThe list of the classes used for searching the objects (contain the search results)
input_point_cloudThe point cloud the recuced clouds are based on

Definition at line 848 of file descriptor_surface_based_recognition.cpp.

Loads all available object meshes so they can be used later.

Definition at line 192 of file descriptor_surface_based_recognition.cpp.

Paints the results of the 2D recognition (bounding box, feature points & orientation triangle) to the given scene image.

Parameters:
pose_recA pointer to the recognition class containing the results for a specific object
scene_imageA pointer to the scene image the results are painted on

Definition at line 708 of file descriptor_surface_based_recognition.cpp.

bool descriptor_surface_based_recognition::DescriptorSurfaceBasedRecognition::processClearAllRecognizersRequest ( ClearAllRecognizers::Request &  req,
ClearAllRecognizers::Response &  res 
) [private]

Processes the request to clear all recognizers

Parameters:
reqthe request message
resthe correlated response message.

Definition at line 186 of file descriptor_surface_based_recognition.cpp.

bool descriptor_surface_based_recognition::DescriptorSurfaceBasedRecognition::processGetObjectListRequest ( GetObjectList::Request &  req,
GetObjectList::Response &  res 
) [private]

Processes the request to get a list of all objects it is searched for

Parameters:
reqthe request message
resthe correlated response message.

Definition at line 177 of file descriptor_surface_based_recognition.cpp.

bool descriptor_surface_based_recognition::DescriptorSurfaceBasedRecognition::processGetRecognizerRequest ( GetRecognizer::Request &  req,
GetRecognizer::Response &  res 
) [private]

Processes the request to recognize the given object

Parameters:
reqthe request message
resthe correlated response message.

Definition at line 157 of file descriptor_surface_based_recognition.cpp.

bool descriptor_surface_based_recognition::DescriptorSurfaceBasedRecognition::processReleaseRecognizerRequest ( ReleaseRecognizer::Request &  req,
ReleaseRecognizer::Response &  res 
) [private]

Processes the request to release a previously created recognizer.

Parameters:
reqthe request message
resthe correlated response message.

Definition at line 171 of file descriptor_surface_based_recognition.cpp.

void descriptor_surface_based_recognition::DescriptorSurfaceBasedRecognition::rosCallback ( const sensor_msgs::ImageConstPtr &  input_image_guppy,
const sensor_msgs::ImageConstPtr &  input_image_guppy_mono,
const sensor_msgs::PointCloud2ConstPtr &  input_point_cloud_with_guppy 
) [private]

The callback function for the ros subscriptions (images and point cloud; called for every new frame)

Parameters:
input_image_guppyThe colored image received by the camera the topic IMAGE_COLOR_TOPIC belongs to
input_image_guppy_monoThe greyscale image received by the camera the topic IMAGE_MONO_TOPIC belongs to
input_point_cloud_with_guppyThe point cloud received by the device the topic POINT_CLOUD_TOPIC belongs to

Definition at line 275 of file descriptor_surface_based_recognition.cpp.

bool descriptor_surface_based_recognition::DescriptorSurfaceBasedRecognition::startObjectRecognition ( std::string  name,
int  count,
bool  use_pose_val 
) [private]

Adds an object to the list of searchable objects.

Parameters:
nameThe name of the object
countThe number of instances the system searches for
use_pose_valIndicates whether a pose validation is used for this object
Returns:
True if the object was added successfully, false otherwise

Definition at line 204 of file descriptor_surface_based_recognition.cpp.

Removes an object from the list of searchable objects.

Parameters:
nameThe name of the object

Definition at line 261 of file descriptor_surface_based_recognition.cpp.

The task given to each thread in the threadpool (=> Search a specific object)

Parameters:
pose_recThe class which contains all relevant data for the search of the object and is used for the search itself

Definition at line 487 of file descriptor_surface_based_recognition.cpp.


Member Data Documentation

Definition at line 148 of file descriptor_surface_based_recognition.h.

Definition at line 137 of file descriptor_surface_based_recognition.h.

Definition at line 149 of file descriptor_surface_based_recognition.h.

The configuration file containing the dynamic parameters of this system

Definition at line 126 of file descriptor_surface_based_recognition.h.

A counter for the processed frames (used only during evaluation)

Definition at line 179 of file descriptor_surface_based_recognition.h.

Definition at line 136 of file descriptor_surface_based_recognition.h.

Ros service handlers used for handling requests

Definition at line 134 of file descriptor_surface_based_recognition.h.

The name of the topic the colored input image is published on

Definition at line 95 of file descriptor_surface_based_recognition.h.

Definition at line 130 of file descriptor_surface_based_recognition.h.

The name of the topic the greyscale input image is published on

Definition at line 98 of file descriptor_surface_based_recognition.h.

Definition at line 150 of file descriptor_surface_based_recognition.h.

Ros subscription filters which will only pass the received messages they subscribed to (=> see input topics above)

Definition at line 129 of file descriptor_surface_based_recognition.h.

A list containing the positions of the found objects of the last frame in the image used for 2D-recognition

Definition at line 167 of file descriptor_surface_based_recognition.h.

Definition at line 147 of file descriptor_surface_based_recognition.h.

A list containing the loaded meshes which can be used for pose validation

Definition at line 164 of file descriptor_surface_based_recognition.h.

Definition at line 155 of file descriptor_surface_based_recognition.h.

Arrays containing the object markers and the reduced clouds' bounding boxes of the current frame

Definition at line 154 of file descriptor_surface_based_recognition.h.

Ros' interface for creating subscribers, publishers, etc.

Definition at line 120 of file descriptor_surface_based_recognition.h.

Definition at line 140 of file descriptor_surface_based_recognition.h.

Definition at line 139 of file descriptor_surface_based_recognition.h.

A list containing the loaded objects which can be recognized

Definition at line 161 of file descriptor_surface_based_recognition.h.

Ros publishers which manage the advertisement of specific topics (=> see output topics above)

Definition at line 146 of file descriptor_surface_based_recognition.h.

The name of the topic the reduced point clouds are published on

Definition at line 113 of file descriptor_surface_based_recognition.h.

The name of the topic the results of the texture search are published on

Definition at line 116 of file descriptor_surface_based_recognition.h.

The name of the topic the visualized bounding boxes around the found objects are published on

Definition at line 110 of file descriptor_surface_based_recognition.h.

The name of the topic the object visualizations are published on

Definition at line 107 of file descriptor_surface_based_recognition.h.

The name of the topic the found objects are published on as asr_msgs

Definition at line 104 of file descriptor_surface_based_recognition.h.

Evaluation ofstream (poses)

Definition at line 176 of file descriptor_surface_based_recognition.h.

Evaluation ofstream (times)

Definition at line 173 of file descriptor_surface_based_recognition.h.

Definition at line 131 of file descriptor_surface_based_recognition.h.

The name of the topic the input point cloud is published on

Definition at line 101 of file descriptor_surface_based_recognition.h.

Used for (optional) validation of found objects

Definition at line 170 of file descriptor_surface_based_recognition.h.

dynamic_reconfigure::Server<DescriptorSurfaceBasedRecognitionConfig> descriptor_surface_based_recognition::DescriptorSurfaceBasedRecognition::reconfigure_server_ [private]

Dynamic reconfigure server which keeps track of the callback function

Definition at line 123 of file descriptor_surface_based_recognition.h.

Definition at line 135 of file descriptor_surface_based_recognition.h.

The policy the subscribers are synced with

Definition at line 143 of file descriptor_surface_based_recognition.h.

Threadpool used to parallelize the search tasks

Definition at line 158 of file descriptor_surface_based_recognition.h.


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


asr_descriptor_surface_based_recognition
Author(s): Allgeyer Tobias, Hutmacher Robin, Meißner Pascal
autogenerated on Thu Jun 6 2019 17:57:30