#include <asrPosePredictionEngine.h>
Public Member Functions | |
asrPosePredictionEngine (std::string pathToXML, std::string sceneName, std::vector< boost::shared_ptr< asr_msgs::AsrObject >> objects, int votes, std::string base_frame) | |
asrPosePredictionEngine (std::string pathToXML, std::string sceneName, std::string reference_object_name, Eigen::Vector3f reference_object_position, Eigen::Vector4f reference_object_orientation, int votes, std::string base_frame) | |
unsigned int | getNumberOfMissingObjects () |
ASR::asrSceneGraphNodePtr | getSceneGraphRoot () |
void | publishHypothesisMessages (std::vector< ASR::AttributedPoint > hypothesis_list) |
Private Attributes | |
std::string | baseFrameId |
std::vector< boost::shared_ptr< asr_msgs::AsrObject > > | evidence_buffer |
ros::Publisher | hypothesis_publisher |
ProbabilisticSceneRecognition::ObjectTransformation | mObjectTransform |
int | number_objects_in_scene |
int | number_obsereved_objects |
int | number_of_votes |
std::string | path |
bool | print_debug_messages |
bool | publish_hypothesis |
std::string | publish_hypothesis_topic |
std::string | reference_object |
ASR::asrSceneGraphNodePtr | root |
std::string | scene_name |
int | votes_per_node |
This class provides a interface to build a psm scene graph and to generate hypothesis for the poses of the unobserved objects in the scene. Observed objects can be marked as explored and the scene graph and the hypothesis are then updated.
Definition at line 46 of file asrPosePredictionEngine.h.
ASR::asrPosePredictionEngine::asrPosePredictionEngine | ( | std::string | pathToXML, |
std::string | sceneName, | ||
std::vector< boost::shared_ptr< asr_msgs::AsrObject >> | objects, | ||
int | votes = 100 , |
||
std::string | base_frame = "/map" |
||
) |
Builds a scene graph which is described in the scene model xml file. The given objects are integreted into the scene graph.
pathToXML | - the path to the scene model xml file. The model has to be formatted like the models from the probabilistic scene model. |
sceneName | - the name of the scene. Only hypothesis for this scene are generated. |
objects | - the list of the observed objects which should be integrated. The first object is the reference object. |
votes | - the overall number of hypothesis that should be generated. The amount of votes is distributed over all unobserved objects. |
base_frame | - the id of the base coordinate system all objects and hypothesis should be transformed to |
Definition at line 23 of file asrPosePredictionEngine.cpp.
ASR::asrPosePredictionEngine::asrPosePredictionEngine | ( | std::string | pathToXML, |
std::string | sceneName, | ||
std::string | reference_object_name, | ||
Eigen::Vector3f | reference_object_position, | ||
Eigen::Vector4f | reference_object_orientation, | ||
int | votes = 100 , |
||
std::string | base_frame = "/map" |
||
) |
Builds a scene graph which is described in the scene model xml file.
pathToXML | - the path to the scene model xml file. The model has to be formatted like the models from the probabilistic scene model. |
sceneName | - the name of the scene. Only hypothesis for this scene are generated. |
reference_object_name | - the name of the reference object. This can be the first observed object. |
reference_object_position | - the position of the reference object. All generated hypotheses are ralative to the position of the reference object. |
votes | - the overall number of hypothesis that should be generated. The amount of votes is distributed over all unobserved objects. |
base_frame | - the id of the base coordinate system all objects and hypothesis should be transformed to |
Definition at line 94 of file asrPosePredictionEngine.cpp.
|
inline |
Returns the number of unobserved objects in the scene.
Definition at line 118 of file asrPosePredictionEngine.h.
|
inline |
Returns the root node of the scene graph
Definition at line 125 of file asrPosePredictionEngine.h.
void ASR::asrPosePredictionEngine::publishHypothesisMessages | ( | std::vector< ASR::AttributedPoint > | hypothesis_list | ) |
Publishs the given points as GEOMETRY::MSG::POSE under the in the launch file defined topic. This standart topic name is "pose_prediction_psm_hypothesis"
hypothesis_list | - the list of AttributedPoints that should be published. |
Definition at line 360 of file asrPosePredictionEngine.cpp.
|
private |
Definition at line 66 of file asrPosePredictionEngine.h.
|
private |
Definition at line 76 of file asrPosePredictionEngine.h.
|
private |
Definition at line 75 of file asrPosePredictionEngine.h.
|
private |
Definition at line 69 of file asrPosePredictionEngine.h.
|
private |
Definition at line 61 of file asrPosePredictionEngine.h.
|
private |
Definition at line 60 of file asrPosePredictionEngine.h.
|
private |
Definition at line 62 of file asrPosePredictionEngine.h.
|
private |
Definition at line 51 of file asrPosePredictionEngine.h.
|
private |
Definition at line 73 of file asrPosePredictionEngine.h.
|
private |
Definition at line 72 of file asrPosePredictionEngine.h.
|
private |
Definition at line 74 of file asrPosePredictionEngine.h.
|
private |
Definition at line 53 of file asrPosePredictionEngine.h.
|
private |
Definition at line 58 of file asrPosePredictionEngine.h.
|
private |
Definition at line 55 of file asrPosePredictionEngine.h.
|
private |
Definition at line 63 of file asrPosePredictionEngine.h.