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 initialize ()
bool isDoorOpen (size_t idx)
bool isObjectApproachable (const std::string &object_name, const bwi::Point2f &current_location)
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::map< int,
boost::shared_ptr
< bwi_mapper::PathFinder > > 
door_approachable_space_1_
std::map< int,
boost::shared_ptr
< bwi_mapper::PathFinder > > 
door_approachable_space_2_
std::vector
< bwi_planning_common::Door
doors_
std::string global_frame_id_
nav_msgs::OccupancyGrid inflated_map_with_doors_
nav_msgs::MapMetaData info_
bool initialized_
std::vector< int32_t > location_map_
std::vector< std::string > locations_
ros::ServiceClient make_plan_client_
bool make_plan_client_initialized_
nav_msgs::OccupancyGrid map_
nav_msgs::OccupancyGrid map_with_doors_
boost::shared_ptr
< ros::NodeHandle
nh_
std::map< std::string,
geometry_msgs::Pose
object_approach_map_
std::map< std::string,
boost::shared_ptr
< bwi_mapper::PathFinder > > 
object_approachable_space_

Detailed Description

Definition at line 53 of file segbot_logical_translator.h.


Constructor & Destructor Documentation

Definition at line 53 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 202 of file segbot_logical_translator.cpp.

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

Definition at line 103 of file segbot_logical_translator.h.

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

Definition at line 118 of file segbot_logical_translator.h.

Definition at line 343 of file segbot_logical_translator.cpp.

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

Definition at line 93 of file segbot_logical_translator.h.

Definition at line 112 of file segbot_logical_translator.h.

Definition at line 124 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 80 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 267 of file segbot_logical_translator.cpp.

Definition at line 58 of file segbot_logical_translator.cpp.

Definition at line 116 of file segbot_logical_translator.cpp.

bool segbot_logical_translator::SegbotLogicalTranslator::isObjectApproachable ( const std::string &  object_name,
const bwi::Point2f current_location 
)

Definition at line 247 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 325 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 299 of file segbot_logical_translator.cpp.


Member Data Documentation

Definition at line 133 of file segbot_logical_translator.h.

Definition at line 134 of file segbot_logical_translator.h.

Definition at line 132 of file segbot_logical_translator.h.

Definition at line 130 of file segbot_logical_translator.h.

Definition at line 143 of file segbot_logical_translator.h.

Definition at line 144 of file segbot_logical_translator.h.

Definition at line 150 of file segbot_logical_translator.h.

Definition at line 137 of file segbot_logical_translator.h.

Definition at line 136 of file segbot_logical_translator.h.

Definition at line 147 of file segbot_logical_translator.h.

Definition at line 148 of file segbot_logical_translator.h.

nav_msgs::OccupancyGrid segbot_logical_translator::SegbotLogicalTranslator::map_ [protected]

Definition at line 141 of file segbot_logical_translator.h.

Definition at line 142 of file segbot_logical_translator.h.

Definition at line 146 of file segbot_logical_translator.h.

Definition at line 138 of file segbot_logical_translator.h.

Definition at line 139 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 Thu Aug 27 2015 15:11:22