#include <tidyup_planning_scene_updater.h>
Classes | |
struct | Door |
Public Member Functions | |
virtual | ~TidyupPlanningSceneUpdater () |
Static Public Member Functions | |
static bool | readState (const string &robotLocation, predicateCallbackType predicateCallback, numericalFluentCallbackType numericalFluentCallback, geometry_msgs::Pose &robotPose, std::map< std::string, geometry_msgs::Pose > &movableObjects, std::map< std::string, std::string > &graspedObjects, std::map< std::string, std::string > &objectsOnStatic, std::set< std::string > &openDoors) |
static bool | update (const geometry_msgs::Pose &robotPose, const std::map< std::string, geometry_msgs::Pose > &movableObjects, const std::map< std::string, std::string > &graspedObjects, const std::set< std::string > &openDoors) |
Private Member Functions | |
bool | fillPoseFromState (geometry_msgs::Pose &pose, const std::string &poseName, numericalFluentCallbackType numericalFluentCallback) |
void | loadDoorPoses (const string &doorLocationFileName) |
bool | readState_ (const string &robotLocation, predicateCallbackType predicateCallback, numericalFluentCallbackType numericalFluentCallback, geometry_msgs::Pose &robotPose, std::map< std::string, geometry_msgs::Pose > &movableObjects, std::map< std::string, std::string > &graspedObjects, std::map< std::string, std::string > &objectsOnStatic, std::set< std::string > &openDoors) |
TidyupPlanningSceneUpdater () | |
bool | update_ (const geometry_msgs::Pose &robotPose, const std::map< std::string, geometry_msgs::Pose > &movableObjects, const std::map< std::string, std::string > &graspedObjects, const std::set< std::string > &openDoors) |
Private Attributes | |
geometry_msgs::Pose | defaultAttachPose |
map< string, Door > | doors |
std::string | logName |
Static Private Attributes | |
static TidyupPlanningSceneUpdater * | instance = NULL |
Definition at line 18 of file tidyup_planning_scene_updater.h.
TidyupPlanningSceneUpdater::~TidyupPlanningSceneUpdater | ( | ) | [virtual] |
Definition at line 39 of file tidyup_planning_scene_updater.cpp.
TidyupPlanningSceneUpdater::TidyupPlanningSceneUpdater | ( | ) | [private] |
Definition at line 22 of file tidyup_planning_scene_updater.cpp.
bool TidyupPlanningSceneUpdater::fillPoseFromState | ( | geometry_msgs::Pose & | pose, |
const std::string & | poseName, | ||
numericalFluentCallbackType | numericalFluentCallback | ||
) | [private] |
Definition at line 224 of file tidyup_planning_scene_updater.cpp.
void TidyupPlanningSceneUpdater::loadDoorPoses | ( | const string & | doorLocationFileName | ) | [private] |
Definition at line 260 of file tidyup_planning_scene_updater.cpp.
bool TidyupPlanningSceneUpdater::readState | ( | const string & | robotLocation, |
predicateCallbackType | predicateCallback, | ||
numericalFluentCallbackType | numericalFluentCallback, | ||
geometry_msgs::Pose & | robotPose, | ||
std::map< std::string, geometry_msgs::Pose > & | movableObjects, | ||
std::map< std::string, std::string > & | graspedObjects, | ||
std::map< std::string, std::string > & | objectsOnStatic, | ||
std::set< std::string > & | openDoors | ||
) | [static] |
Definition at line 43 of file tidyup_planning_scene_updater.cpp.
bool TidyupPlanningSceneUpdater::readState_ | ( | const string & | robotLocation, |
predicateCallbackType | predicateCallback, | ||
numericalFluentCallbackType | numericalFluentCallback, | ||
geometry_msgs::Pose & | robotPose, | ||
std::map< std::string, geometry_msgs::Pose > & | movableObjects, | ||
std::map< std::string, std::string > & | graspedObjects, | ||
std::map< std::string, std::string > & | objectsOnStatic, | ||
std::set< std::string > & | openDoors | ||
) | [private] |
Definition at line 57 of file tidyup_planning_scene_updater.cpp.
bool TidyupPlanningSceneUpdater::update | ( | const geometry_msgs::Pose & | robotPose, |
const std::map< std::string, geometry_msgs::Pose > & | movableObjects, | ||
const std::map< std::string, std::string > & | graspedObjects, | ||
const std::set< std::string > & | openDoors | ||
) | [static] |
Definition at line 146 of file tidyup_planning_scene_updater.cpp.
bool TidyupPlanningSceneUpdater::update_ | ( | const geometry_msgs::Pose & | robotPose, |
const std::map< std::string, geometry_msgs::Pose > & | movableObjects, | ||
const std::map< std::string, std::string > & | graspedObjects, | ||
const std::set< std::string > & | openDoors | ||
) | [private] |
Definition at line 155 of file tidyup_planning_scene_updater.cpp.
Definition at line 60 of file tidyup_planning_scene_updater.h.
map<string, Door> TidyupPlanningSceneUpdater::doors [private] |
Definition at line 68 of file tidyup_planning_scene_updater.h.
TidyupPlanningSceneUpdater * TidyupPlanningSceneUpdater::instance = NULL [static, private] |
Definition at line 70 of file tidyup_planning_scene_updater.h.
std::string TidyupPlanningSceneUpdater::logName [private] |
Definition at line 59 of file tidyup_planning_scene_updater.h.