Public Member Functions | Private Member Functions | Private Attributes | List of all members
recognizer_prediction_ism::PosePrediction Class Reference

#include <pose_prediction.h>

Public Member Functions

 PosePrediction (std::vector< ISM::RecognitionResultPtr > &results_already_in_shared, SharedRecognitionResultsManagerPtr shared_recognition_results_ptr)
 
bool processGetPointCloudServiceCall (asr_recognizer_prediction_ism::GetPointCloud::Request &req, asr_recognizer_prediction_ism::GetPointCloud::Response &res)
 RecognizerPredictionISM::processGetPointCloudServiceCall Callback function for a GetPointCloud Request The point cloud is empty if there is no result. In the debug mode this method publishes a point cloud of the object hypotheses. More...
 
 ~PosePrediction ()
 

Private Member Functions

void checkPointCloud (asr_msgs::AsrAttributedPointCloud attributed_point_cloud)
 
void dynamicReconfCallback (asr_recognizer_prediction_ism::pose_predictionConfig &config, uint32_t level)
 
void visualize (ISM::RecognitionResult recognition_result, char *result_specifier, int *i, unsigned int sampled_results_size, asr_msgs::AsrAttributedPointCloud *union_attributed_point_cloud, std::set< std::pair< std::string, std::string >> *predicted_objects)
 

Private Attributes

std::string database_filename_
 
ros::ServiceClient found_object_client_
 
bool is_visualization_active_
 
ros::NodeHandle node_handle_
 
double percentage_of_records_for_prediction_
 
ros::ServiceServer point_cloud_server_
 
ros::Publisher pose_prediction_markers_publisher_
 
VIZ::PosePredictionVisualizerPtr pose_prediction_visualizer_ptr_
 
pose_prediction_ism::PosePredictorPtr pose_predictor_ptr_
 
double prediction_generation_factor_
 
dynamic_reconfigure::Server< asr_recognizer_prediction_ism::pose_predictionConfig > * reconfigure_server_
 
VIZ::ISMResultVisualizerRVIZPtr res_visualizer_
 
ResamplerPtr resampler_ptr_
 
std::vector< ISM::RecognitionResultPtr > & results_already_shared_
 
std::vector< ISM::RecognitionResultPtr > results_buffer_
 
ros::Publisher scene_markers_publisher_
 
ros::ServiceServer toggle_pose_predictor_server_
 
ros::ServiceServer toggle_visualization_server_
 

Detailed Description

Definition at line 43 of file pose_prediction.h.

Constructor & Destructor Documentation

recognizer_prediction_ism::PosePrediction::PosePrediction ( std::vector< ISM::RecognitionResultPtr > &  results_already_in_shared,
SharedRecognitionResultsManagerPtr  shared_recognition_results_ptr 
)

Definition at line 43 of file pose_prediction.cpp.

recognizer_prediction_ism::PosePrediction::~PosePrediction ( )
inline

Definition at line 51 of file pose_prediction.h.

Member Function Documentation

void recognizer_prediction_ism::PosePrediction::checkPointCloud ( asr_msgs::AsrAttributedPointCloud  attributed_point_cloud)
private

Definition at line 260 of file pose_prediction.cpp.

void recognizer_prediction_ism::PosePrediction::dynamicReconfCallback ( asr_recognizer_prediction_ism::pose_predictionConfig &  config,
uint32_t  level 
)
private

Definition at line 99 of file pose_prediction.cpp.

bool recognizer_prediction_ism::PosePrediction::processGetPointCloudServiceCall ( asr_recognizer_prediction_ism::GetPointCloud::Request &  req,
asr_recognizer_prediction_ism::GetPointCloud::Response &  res 
)

RecognizerPredictionISM::processGetPointCloudServiceCall Callback function for a GetPointCloud Request The point cloud is empty if there is no result. In the debug mode this method publishes a point cloud of the object hypotheses.

Parameters
reqGiven GetPointCloud request
resThe GetPointCloud response
Returns
Returns false, if the found object call is not available

Definition at line 131 of file pose_prediction.cpp.

void recognizer_prediction_ism::PosePrediction::visualize ( ISM::RecognitionResult  recognition_result,
char *  result_specifier,
int *  i,
unsigned int  sampled_results_size,
asr_msgs::AsrAttributedPointCloud *  union_attributed_point_cloud,
std::set< std::pair< std::string, std::string >> *  predicted_objects 
)
private

Definition at line 236 of file pose_prediction.cpp.

Member Data Documentation

std::string recognizer_prediction_ism::PosePrediction::database_filename_
private

Definition at line 70 of file pose_prediction.h.

ros::ServiceClient recognizer_prediction_ism::PosePrediction::found_object_client_
private

Definition at line 83 of file pose_prediction.h.

bool recognizer_prediction_ism::PosePrediction::is_visualization_active_
private

Definition at line 92 of file pose_prediction.h.

ros::NodeHandle recognizer_prediction_ism::PosePrediction::node_handle_
private

Definition at line 78 of file pose_prediction.h.

double recognizer_prediction_ism::PosePrediction::percentage_of_records_for_prediction_
private

Definition at line 68 of file pose_prediction.h.

ros::ServiceServer recognizer_prediction_ism::PosePrediction::point_cloud_server_
private

Definition at line 79 of file pose_prediction.h.

ros::Publisher recognizer_prediction_ism::PosePrediction::pose_prediction_markers_publisher_
private

Definition at line 86 of file pose_prediction.h.

VIZ::PosePredictionVisualizerPtr recognizer_prediction_ism::PosePrediction::pose_prediction_visualizer_ptr_
private

Definition at line 93 of file pose_prediction.h.

pose_prediction_ism::PosePredictorPtr recognizer_prediction_ism::PosePrediction::pose_predictor_ptr_
private

Definition at line 66 of file pose_prediction.h.

double recognizer_prediction_ism::PosePrediction::prediction_generation_factor_
private

Definition at line 69 of file pose_prediction.h.

dynamic_reconfigure::Server<asr_recognizer_prediction_ism::pose_predictionConfig>* recognizer_prediction_ism::PosePrediction::reconfigure_server_
private

Definition at line 88 of file pose_prediction.h.

VIZ::ISMResultVisualizerRVIZPtr recognizer_prediction_ism::PosePrediction::res_visualizer_
private

Definition at line 94 of file pose_prediction.h.

ResamplerPtr recognizer_prediction_ism::PosePrediction::resampler_ptr_
private

Definition at line 67 of file pose_prediction.h.

std::vector<ISM::RecognitionResultPtr>& recognizer_prediction_ism::PosePrediction::results_already_shared_
private

Definition at line 73 of file pose_prediction.h.

std::vector<ISM::RecognitionResultPtr> recognizer_prediction_ism::PosePrediction::results_buffer_
private

Definition at line 75 of file pose_prediction.h.

ros::Publisher recognizer_prediction_ism::PosePrediction::scene_markers_publisher_
private

Definition at line 85 of file pose_prediction.h.

ros::ServiceServer recognizer_prediction_ism::PosePrediction::toggle_pose_predictor_server_
private

Definition at line 81 of file pose_prediction.h.

ros::ServiceServer recognizer_prediction_ism::PosePrediction::toggle_visualization_server_
private

Definition at line 80 of file pose_prediction.h.


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


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