#include <grid_initialisation.hpp>

Public Member Functions | |
| GridInitialisation (std::string gridFilePath) | |
| bool | initHandler () |
| bool | resetHandler () |
| virtual | ~GridInitialisation () |
Public Member Functions inherited from directSearchWS::DirectSearchHandler | |
| virtual bool | backToInitial (const SearchedObjectTypesAndIds &searchedObjectTypesAndIds) |
| DirectSearchHandler () | |
| PosePtr | getActualCameraPosePtr () const |
| SearchedObjectTypesAndIds | getActualFilteredSearchedObjectTypesAndIds () const |
| PtuTuplePtr | getActualPtuPtr () const |
| PosePtr | getActualRobotPosePtr () const |
| bool | getArePosesFromDemonstrationLeft () const |
| bool | getIsNoPoseLeft () const |
| bool | getIsSameRobotPoseAsBefore () const |
| virtual bool | getNextRobotState (const SearchedObjectTypesAndIds &searchedObjectTypesAndIds) |
| double | getRemainingPosesDistances () const |
| int | getRemainingPTUPoses () const |
| int | getRemainingRobotPoses () const |
| virtual | ~DirectSearchHandler () |
Private Member Functions | |
| double | getYaw (const geometry_msgs::Point &pointA, const geometry_msgs::Point &pointB) const |
| void | initPTUPoses () |
Private Attributes | |
| double | clearVision |
| std::string | gridFilePath |
| PtuTuplePtrVecPtr | ptuTuplePtrVecPtr |
Additional Inherited Members | |
Protected Member Functions inherited from directSearchWS::DirectSearchHandler | |
| void | calculateRemainingPosesDistances () |
Protected Attributes inherited from directSearchWS::DirectSearchHandler | |
| bool | arePosesFromDemonstrationLeft |
| bool | isNoPoseLeft |
| bool | isRobotPoseChanged |
| bool | isSameRobotPoseAsBefore |
| PosePtr | nextCameraPosePtr |
| SearchedObjectTypesAndIds | nextFilteredSearchedObjectTypesAndIds |
| PtuTuplePtr | nextPtuPtr |
| PosePtr | nextRobotPosePtr |
| PoseHelperPtr | poseHelperPtr |
| RobotStatePtrVecPtr | posesToExplorePtr |
| double | remainingPosesDistances |
Definition at line 25 of file grid_initialisation.hpp.
| directSearchWS::GridInitialisation::GridInitialisation | ( | std::string | gridFilePath | ) |
Definition at line 22 of file grid_initialisation.cpp.
|
virtual |
Definition at line 26 of file grid_initialisation.cpp.
|
private |
Definition at line 194 of file grid_initialisation.cpp.
|
virtual |
Implements directSearchWS::DirectSearchHandler.
Definition at line 72 of file grid_initialisation.cpp.
|
private |
Definition at line 28 of file grid_initialisation.cpp.
|
virtual |
Reimplemented from directSearchWS::DirectSearchHandler.
Definition at line 64 of file grid_initialisation.cpp.
|
private |
Definition at line 32 of file grid_initialisation.hpp.
|
private |
Definition at line 28 of file grid_initialisation.hpp.
|
private |
Definition at line 30 of file grid_initialisation.hpp.