Public Member Functions | Protected Attributes
segbot_logical_translator::SegbotLogicalTranslator Class Reference

#include <segbot_logical_translator.h>

Inheritance diagram for segbot_logical_translator::SegbotLogicalTranslator:
Inheritance graph
[legend]

List of all members.

Public Member Functions

bool getApproachPoint (size_t idx, const bwi::Point2f &current_location, bwi::Point2f &point, float &yaw)
size_t getDoorIdx (const std::string &door_str) const
std::string getDoorString (size_t idx) const
size_t getLocationIdx (const bwi::Point2f &current_location)
size_t getLocationIdx (const std::string &loc_str) const
std::string getLocationString (size_t idx) const
size_t getNumDoors () const
bool getObjectApproachLocation (const std::string &object_name, geometry_msgs::Pose &pose)
bool getThroughDoorPoint (size_t idx, const bwi::Point2f &current_location, bwi::Point2f &point, float &yaw)
bool isDoorOpen (size_t idx)
bool isRobotBesideDoor (const bwi::Point2f &current_location, float yaw, float threshold, size_t idx)
bool isRobotFacingDoor (const bwi::Point2f &current_location, float yaw, float threshold, size_t idx)
 SegbotLogicalTranslator ()

Protected Attributes

std::vector
< bwi_planning_common::Door > 
doors_
std::string global_frame_id_
nav_msgs::MapMetaData info_
std::vector< int32_t > location_map_
std::vector< std::string > locations_
ros::ServiceClient make_plan_client_
boost::shared_ptr
< bwi_mapper::MapLoader > 
mapper_
boost::shared_ptr
< ros::NodeHandle
nh_
std::map< std::string,
geometry_msgs::Pose
object_approach_map_

Detailed Description

Definition at line 52 of file segbot_logical_translator.h.


Constructor & Destructor Documentation

Definition at line 50 of file segbot_logical_translator.cpp.


Member Function Documentation

bool segbot_logical_translator::SegbotLogicalTranslator::getApproachPoint ( size_t  idx,
const bwi::Point2f &  current_location,
bwi::Point2f &  point,
float &  yaw 
)

Definition at line 156 of file segbot_logical_translator.cpp.

size_t segbot_logical_translator::SegbotLogicalTranslator::getDoorIdx ( const std::string &  door_str) const [inline]

Definition at line 98 of file segbot_logical_translator.h.

std::string segbot_logical_translator::SegbotLogicalTranslator::getDoorString ( size_t  idx) const [inline]

Definition at line 113 of file segbot_logical_translator.h.

size_t segbot_logical_translator::SegbotLogicalTranslator::getLocationIdx ( const bwi::Point2f &  current_location)
size_t segbot_logical_translator::SegbotLogicalTranslator::getLocationIdx ( const std::string &  loc_str) const [inline]

Definition at line 88 of file segbot_logical_translator.h.

Definition at line 107 of file segbot_logical_translator.h.

Definition at line 119 of file segbot_logical_translator.h.

bool segbot_logical_translator::SegbotLogicalTranslator::getObjectApproachLocation ( const std::string &  object_name,
geometry_msgs::Pose pose 
) [inline]

Definition at line 75 of file segbot_logical_translator.h.

bool segbot_logical_translator::SegbotLogicalTranslator::getThroughDoorPoint ( size_t  idx,
const bwi::Point2f &  current_location,
bwi::Point2f &  point,
float &  yaw 
)

Definition at line 182 of file segbot_logical_translator.cpp.

Definition at line 97 of file segbot_logical_translator.cpp.

bool segbot_logical_translator::SegbotLogicalTranslator::isRobotBesideDoor ( const bwi::Point2f &  current_location,
float  yaw,
float  threshold,
size_t  idx 
)

Definition at line 231 of file segbot_logical_translator.cpp.

bool segbot_logical_translator::SegbotLogicalTranslator::isRobotFacingDoor ( const bwi::Point2f &  current_location,
float  yaw,
float  threshold,
size_t  idx 
)

Definition at line 209 of file segbot_logical_translator.cpp.


Member Data Documentation

std::vector<bwi_planning_common::Door> segbot_logical_translator::SegbotLogicalTranslator::doors_ [protected]

Definition at line 127 of file segbot_logical_translator.h.

Definition at line 125 of file segbot_logical_translator.h.

Definition at line 133 of file segbot_logical_translator.h.

Definition at line 129 of file segbot_logical_translator.h.

Definition at line 128 of file segbot_logical_translator.h.

Definition at line 136 of file segbot_logical_translator.h.

boost::shared_ptr<bwi_mapper::MapLoader> segbot_logical_translator::SegbotLogicalTranslator::mapper_ [protected]

Definition at line 132 of file segbot_logical_translator.h.

Definition at line 135 of file segbot_logical_translator.h.

Definition at line 130 of file segbot_logical_translator.h.


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


segbot_logical_translator
Author(s): Piyush Khandelwal
autogenerated on Mon Oct 6 2014 07:30:24