Public Member Functions | Private Member Functions | Static Private Member Functions | Private Attributes
fake_object_recognition::FakeObjectRecognition Class Reference

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

#include <fake_object_recognition.h>

List of all members.

Public Member Functions

 FakeObjectRecognition ()
 The constructor of this class.

Private Member Functions

std::array
< geometry_msgs::Point, 8 > 
calculateBB (const ObjectConfig &object)
 calculate approximated oriented bounding box of the object represented by its corner points
void configCallback (FakeObjectRecognitionConfig &config, uint32_t level)
 The callback function which is called when the configuration has changed.
asr_msgs::AsrObjectPtr createAsrMessage (const ObjectConfig &object_config, const geometry_msgs::Pose &pose, const std::string &frame_id)
 Creates a AsrObject-message for a found object.
visualization_msgs::Marker createMarker (const asr_msgs::AsrObjectPtr &object, int id, int lifetime, bool use_col_init=false)
 Creates a visualization marker for a found object.
visualization_msgs::MarkerArray::Ptr createNormalMarker (const ObjectConfig &object, int id, int lifetime)
 publishes normal markers (yellow arrows) for all objects in the configuration
geometry_msgs::Point createPoint (double x, double y, double z)
 creates a Point geometry_msg with the given coordinates
void doRecognition ()
 This function is called whenever objects shall be recognized.
bool getBBfromFile (std::array< geometry_msgs::Point, 8 > &result, std::string object_type)
 try to get bounding box corner points from file.
std::vector< geometry_msgs::PointgetNormals (const ObjectConfig &object)
 get Normals of the object through the object_database/object_meta_data service
void loadObjects ()
 This function loads the objects of the object-config-file.
bool objectIsVisible (const geometry_msgs::Pose &pose_left, const geometry_msgs::Pose &pose_right)
 Checks whether an object is currently visible.
bool objectIsVisible (const std::array< geometry_msgs::Point, 8 > &bb_left, const std::array< geometry_msgs::Point, 8 > &bb_right, const geometry_msgs::Pose &pose_left, const geometry_msgs::Pose &pose_right, const std::vector< geometry_msgs::Point > &normals_left, const std::vector< geometry_msgs::Point > &normals_right)
 Checks whether an object is currently visible.
bool parsePoseString (std::string pose_in, geometry_msgs::Pose &pose_out, std::string delim, std::string angles)
 This function parses the string containing the pose of an entry in the object-config-file.
bool processClearAllRecognizers (ClearAllRecognizers::Request &req, ClearAllRecognizers::Response &res)
bool processGetAllRecognizersRequest (GetAllRecognizers::Request &req, GetAllRecognizers::Response &res)
bool processGetRecognizerRequest (GetRecognizer::Request &req, GetRecognizer::Response &res)
bool processReleaseRecognizerRequest (ReleaseRecognizer::Request &req, ReleaseRecognizer::Response &res)
void timerCallback (const ros::TimerEvent &event)
 The callback function of the timer.
geometry_msgs::Pose transformFrame (const geometry_msgs::Pose &pose, const std::string &frame_from, const std::string &frame_to)
 Transforms a given pose from one frame to another.
std::vector< geometry_msgs::PointtransformPoints (std::vector< geometry_msgs::Point > points_list, Eigen::Quaterniond rotation, Eigen::Vector3d translation)
 Transforms points locally (as opposed to via a ROS service call in transformFrame)
std::array
< geometry_msgs::Point, 8 > 
transformPoints (std::array< geometry_msgs::Point, 8 > points_list, Eigen::Quaterniond rotation, Eigen::Vector3d translation)
 Transforms points locally (as opposed to via a ROS service call in transformFrame)

Static Private Member Functions

static std_msgs::ColorRGBA createColorRGBA (float red, float green, float blue, float alpha)
 Creates a std_msgs::ColorRGBA-message from the given values.
static std_msgs::ColorRGBA getMeshColor (std::string observed_id)
 Returns the color of a mesh based on the object's id (Only creates a color if it is an object of the segmentable category.

Private Attributes

std::string bb_corners_file_name_
std::map< std::string,
std::array
< geometry_msgs::Point, 8 > > 
bounding_box_corners_
ros::ServiceServer clear_all_recognizers_service_
FakeObjectRecognitionConfig config_
bool config_changed_
std::string config_file_path_
ErrorSimulation err_sim_
double fcp_
double fovx_
double fovy_
std::string frame_camera_left_
std::string frame_camera_right_
std::string frame_world_
ros::Publisher generated_constellation_marker_pub_
ros::ServiceServer get_all_recognizers_service_
ros::ServiceServer get_recognizer_service_
tf::TransformListener listener_
double ncp_
ros::NodeHandle nh_
std::map< std::string,
std::vector
< geometry_msgs::Point > > 
normals_
std::string object_database_name_
ros::ServiceClient object_metadata_service_client_
ros::Publisher object_normals_pub_
std::vector< ObjectConfigobjects_
std::vector< std::string > objects_to_rec_
std::string output_constellation_marker_topic_
std::string output_normals_topic_
std::string output_rec_markers_topic_
std::string output_rec_objects_topic_
double rating_threshold_
double rating_threshold_d_
double rating_threshold_x_
double rating_threshold_y_
bool recognition_released_
ros::Publisher recognized_objects_marker_pub_
ros::Publisher recognized_objects_pub_
dynamic_reconfigure::Server
< FakeObjectRecognitionConfig > 
reconfigure_server_
ros::ServiceServer release_recognizer_service_
ros::Timer timer_
double timer_duration_

Detailed Description

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

Definition at line 65 of file fake_object_recognition.h.


Constructor & Destructor Documentation

The constructor of this class.

Definition at line 37 of file fake_object_recognition.cpp.


Member Function Documentation

calculate approximated oriented bounding box of the object represented by its corner points

Parameters:
objectto calculate the bounding box corner points for
Returns:
the object's bounding box corner points

Definition at line 749 of file fake_object_recognition.cpp.

void fake_object_recognition::FakeObjectRecognition::configCallback ( FakeObjectRecognitionConfig &  config,
uint32_t  level 
) [private]

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

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

Definition at line 260 of file fake_object_recognition.cpp.

asr_msgs::AsrObjectPtr fake_object_recognition::FakeObjectRecognition::createAsrMessage ( const ObjectConfig object_config,
const geometry_msgs::Pose pose,
const std::string &  frame_id 
) [private]

Creates a AsrObject-message for a found object.

Parameters:
object_configThe configuration file of the found object
poseThe pose of the found object
frame_idThe frame the given pose belongs to
Returns:
The created AsrObject-message

Definition at line 455 of file fake_object_recognition.cpp.

std_msgs::ColorRGBA fake_object_recognition::FakeObjectRecognition::createColorRGBA ( float  red,
float  green,
float  blue,
float  alpha 
) [static, private]

Creates a std_msgs::ColorRGBA-message from the given values.

Parameters:
redThe R-value of the RGBA-color
greenThe G-value of the RGBA-color
blueThe B-value of the RGBA-color
alphaThe A-value of the RGBA-color
Returns:
The created color-message

Definition at line 561 of file fake_object_recognition.cpp.

visualization_msgs::Marker fake_object_recognition::FakeObjectRecognition::createMarker ( const asr_msgs::AsrObjectPtr &  object,
int  id,
int  lifetime,
bool  use_col_init = false 
) [private]

Creates a visualization marker for a found object.

Parameters:
objectThe AsrObject-message created for the found object
idThe id used to distinguish between multiple markers
lifetimeThe lifetime of the marker
use_col_initIf this is true the marker has a special color indicating that this is a marker visualizing an available object
Returns:
The created marker

Definition at line 506 of file fake_object_recognition.cpp.

visualization_msgs::MarkerArray::Ptr fake_object_recognition::FakeObjectRecognition::createNormalMarker ( const ObjectConfig object,
int  id,
int  lifetime 
) [private]

publishes normal markers (yellow arrows) for all objects in the configuration

Parameters:
objectthe ObjectConfig for which to show the normals
idThe id used to distinguish between multiple markers
lifetimeThe lifetime of the marker
Returns:
The created marker

Definition at line 598 of file fake_object_recognition.cpp.

geometry_msgs::Point fake_object_recognition::FakeObjectRecognition::createPoint ( double  x,
double  y,
double  z 
) [private]

creates a Point geometry_msg with the given coordinates

Parameters:
xcoordinate
ycoordinate
zcoordinate
Returns:
geometry_msgs::Point with the given coordinates

Definition at line 951 of file fake_object_recognition.cpp.

This function is called whenever objects shall be recognized.

Definition at line 265 of file fake_object_recognition.cpp.

bool fake_object_recognition::FakeObjectRecognition::getBBfromFile ( std::array< geometry_msgs::Point, 8 > &  result,
std::string  object_type 
) [private]

try to get bounding box corner points from file.

Parameters:
resultthe resulting list of corner points. Contents undefined if false is returned
object_typeType of the ObjectConfig
Returns:
whether bounding box corner point were found (true) or not

Definition at line 682 of file fake_object_recognition.cpp.

std_msgs::ColorRGBA fake_object_recognition::FakeObjectRecognition::getMeshColor ( std::string  observed_id) [static, private]

Returns the color of a mesh based on the object's id (Only creates a color if it is an object of the segmentable category.

Parameters:
observed_idThe id of an object
Returns:
The correlating color

Definition at line 536 of file fake_object_recognition.cpp.

get Normals of the object through the object_database/object_meta_data service

Parameters:
objectto get the normals for
Returns:
vector of the object normals

Definition at line 655 of file fake_object_recognition.cpp.

This function loads the objects of the object-config-file.

Definition at line 103 of file fake_object_recognition.cpp.

Checks whether an object is currently visible.

Parameters:
pose_leftThe pose of the object in the left camera frame
pose_rightThe pose of the object in the right camera frame
Returns:
True if the object is visible, false otherwise

Definition at line 404 of file fake_object_recognition.cpp.

bool fake_object_recognition::FakeObjectRecognition::objectIsVisible ( const std::array< geometry_msgs::Point, 8 > &  bb_left,
const std::array< geometry_msgs::Point, 8 > &  bb_right,
const geometry_msgs::Pose pose_left,
const geometry_msgs::Pose pose_right,
const std::vector< geometry_msgs::Point > &  normals_left,
const std::vector< geometry_msgs::Point > &  normals_right 
) [private]

Checks whether an object is currently visible.

Parameters:
bb_leftBounding box corner points in left camera frame
bb_rightBounding box corner points in right camera frame
pose_leftObject pose in left camera frame
pose_rightObject pose in right camera frame
normals_leftObject sight normals in left camer frame
normals_rightObject sight normals in left camer frame
Returns:
True if the object is visible, false otherwise

Definition at line 429 of file fake_object_recognition.cpp.

bool fake_object_recognition::FakeObjectRecognition::parsePoseString ( std::string  pose_in,
geometry_msgs::Pose pose_out,
std::string  delim,
std::string  angles 
) [private]

This function parses the string containing the pose of an entry in the object-config-file.

Parameters:
pose_inThe given pose string
pose_outThe parsed pose
delimThe string used to split the input pose-string

Definition at line 153 of file fake_object_recognition.cpp.

bool fake_object_recognition::FakeObjectRecognition::processClearAllRecognizers ( ClearAllRecognizers::Request &  req,
ClearAllRecognizers::Response &  res 
) [private]

Processes the request to release all recognizer

Parameters:
reqThe request message
resThe correlated response message.

Definition at line 239 of file fake_object_recognition.cpp.

bool fake_object_recognition::FakeObjectRecognition::processGetAllRecognizersRequest ( GetAllRecognizers::Request &  req,
GetAllRecognizers::Response &  res 
) [private]

Processes the request to recognize all objects loaded from config.xml

Parameters:
reqThe request message
resThe correlated response message.

Definition at line 224 of file fake_object_recognition.cpp.

bool fake_object_recognition::FakeObjectRecognition::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 203 of file fake_object_recognition.cpp.

bool fake_object_recognition::FakeObjectRecognition::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 215 of file fake_object_recognition.cpp.

The callback function of the timer.

Parameters:
eventStructure passed as a parameter to the callback invoked by a ros::Timer

Definition at line 246 of file fake_object_recognition.cpp.

geometry_msgs::Pose fake_object_recognition::FakeObjectRecognition::transformFrame ( const geometry_msgs::Pose pose,
const std::string &  frame_from,
const std::string &  frame_to 
) [private]

Transforms a given pose from one frame to another.

Parameters:
poseThe given pose
frame_fromThe frame the given pose belongs to
frame_toThe frame the pose is transformed to
Returns:
The transformed pose

Definition at line 383 of file fake_object_recognition.cpp.

std::vector< geometry_msgs::Point > fake_object_recognition::FakeObjectRecognition::transformPoints ( std::vector< geometry_msgs::Point points_list,
Eigen::Quaterniond  rotation,
Eigen::Vector3d  translation 
) [private]

Transforms points locally (as opposed to via a ROS service call in transformFrame)

Parameters:
points_listList of Points to transform as a std::vector
rot_matRotation quaternion to transform with (gets normalized in fuction)
translationTranslation vector
Returns:
list of transformed points

Definition at line 572 of file fake_object_recognition.cpp.

std::array< geometry_msgs::Point, 8 > fake_object_recognition::FakeObjectRecognition::transformPoints ( std::array< geometry_msgs::Point, 8 >  points_list,
Eigen::Quaterniond  rotation,
Eigen::Vector3d  translation 
) [private]

Transforms points locally (as opposed to via a ROS service call in transformFrame)

Parameters:
points_listList of Points to transform as a std::array<geometry_msgs::Point, 8> (specifically for bounding box corners)
rot_matRotation quaternion to transform with (gets normalized in fuction)
translationTranslation vector
Returns:
list of transformed points

Definition at line 585 of file fake_object_recognition.cpp.


Member Data Documentation

Name of the file where calculated bounding box corner points are stored

Definition at line 155 of file fake_object_recognition.h.

Map of object names to the object's bounding box corner points

Definition at line 149 of file fake_object_recognition.h.

Definition at line 85 of file fake_object_recognition.h.

FakeObjectRecognitionConfig fake_object_recognition::FakeObjectRecognition::config_ [private]

The configuration containing the dynamic parameters of this process

Definition at line 75 of file fake_object_recognition.h.

This value indicates whether the configuration has changed

Definition at line 78 of file fake_object_recognition.h.

The path to the file containing information about the available objects

Definition at line 112 of file fake_object_recognition.h.

An error simulator used to generate pose errors

Definition at line 143 of file fake_object_recognition.h.

Definition at line 104 of file fake_object_recognition.h.

The parameters of the used cameras

Definition at line 101 of file fake_object_recognition.h.

Definition at line 102 of file fake_object_recognition.h.

Definition at line 108 of file fake_object_recognition.h.

Definition at line 109 of file fake_object_recognition.h.

The used frames (world and cameras)

Definition at line 107 of file fake_object_recognition.h.

Definition at line 91 of file fake_object_recognition.h.

Definition at line 84 of file fake_object_recognition.h.

Ros service handlers used for handling requests

Definition at line 81 of file fake_object_recognition.h.

A listener used to transform between the world and camera frames

Definition at line 140 of file fake_object_recognition.h.

Definition at line 103 of file fake_object_recognition.h.

Ros' interface for creating subscribers, publishers, etc.

Definition at line 69 of file fake_object_recognition.h.

Map of object names to the object's normal vectors

Definition at line 146 of file fake_object_recognition.h.

Name of the database package where object mesh and normal files are stored

Definition at line 158 of file fake_object_recognition.h.

Service client used to request object meta data

Definition at line 152 of file fake_object_recognition.h.

Definition at line 92 of file fake_object_recognition.h.

The available objects

Definition at line 134 of file fake_object_recognition.h.

The objects which shall be recognized

Definition at line 137 of file fake_object_recognition.h.

Definition at line 117 of file fake_object_recognition.h.

Definition at line 118 of file fake_object_recognition.h.

Definition at line 116 of file fake_object_recognition.h.

The topics of the publishers

Definition at line 115 of file fake_object_recognition.h.

The minimum value between 0.0 and 1.0 a normals rating of an object needs to have to be valid

Definition at line 128 of file fake_object_recognition.h.

The minimum value a distance rating of a pose needs to have to be valid

Definition at line 121 of file fake_object_recognition.h.

The minimum value an azimut angle rating of a pose needs to have to be valid

Definition at line 123 of file fake_object_recognition.h.

The minimum value an elevation angle rating of a pose needs to have to be valid

Definition at line 125 of file fake_object_recognition.h.

This value indicates whether the recognition is paused

Definition at line 98 of file fake_object_recognition.h.

Definition at line 90 of file fake_object_recognition.h.

Ros publishers which manage the advertisement of specific topics

Definition at line 89 of file fake_object_recognition.h.

dynamic_reconfigure::Server<FakeObjectRecognitionConfig> fake_object_recognition::FakeObjectRecognition::reconfigure_server_ [private]

Dynamic reconfigure server which keeps track of the callback function

Definition at line 72 of file fake_object_recognition.h.

Definition at line 82 of file fake_object_recognition.h.

A timer which is used to control the recognition cycles

Definition at line 95 of file fake_object_recognition.h.

The time between recognition cycles used by the timer

Definition at line 131 of file fake_object_recognition.h.


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


asr_fake_object_recognition
Author(s): Allgeyer Tobias, Aumann Florian, Borella Jocelyn, Meißner Pascal, Qattan Mohamad
autogenerated on Sat Jun 8 2019 19:15:45