Public Member Functions | Private Member Functions | Private Attributes
FurnitureTracker Class Reference

#include <furniture_tracker.h>

List of all members.

Public Member Functions

 FurnitureTracker ()
 Constructor, initializes data structures containing information about markers and furniture obstacles.
void publishFurniturePoses ()
 publish localization and navigation data for furniture that has recently changed pose

Private Member Functions

void fillFootprintInformation (int index, std::vector< geometry_msgs::Polygon > footprints, rail_ceiling::Obstacles *obstacles, bool isLocalization)
 Calculate footprint polygons and fill them into an obstacles message.
bool getAllPoses (rail_ceiling::GetAllObstacles::Request &req, rail_ceiling::GetAllObstacles::Response &res)
 service callback for returning the most recent set of previously published furniture poses
void markerCallback (const ar_track_alvar_msgs::AlvarMarkers::ConstPtr &msg)
 save updated marker data
void readConfigFiles (std::string markerConfigFile, std::string furnitureConfigFile)
 read marker and furniture configuration data
bool updated (geometry_msgs::Pose2D pose)
 determine whether a pose has been updated after its initialization
void updateMessages (int index, std::string type, rail_ceiling::Obstacles *obstacles)
 update obstacle message data

Private Attributes

ros::ServiceServer allPosesServer
std::vector< FurnitureTransformsfootprintTransforms
ros::Publisher furnitureLayerPub
std::vector< FurniturefurnitureList
std::vector
< geometry_msgs::Pose2D > 
furniturePoses
std::vector
< geometry_msgs::Pose2D > 
lastPublishedPoses
std::vector< MarkermarkerList
std::vector< ros::SubscribermarkerSubscribers
ros::NodeHandle n
bool readInitialPoses
tf::TransformListener tfListener

Detailed Description

Definition at line 48 of file furniture_tracker.h.


Constructor & Destructor Documentation

Constructor, initializes data structures containing information about markers and furniture obstacles.

Definition at line 15 of file furniture_tracker.cpp.


Member Function Documentation

void FurnitureTracker::fillFootprintInformation ( int  index,
std::vector< geometry_msgs::Polygon >  footprints,
rail_ceiling::Obstacles *  obstacles,
bool  isLocalization 
) [private]

Calculate footprint polygons and fill them into an obstacles message.

Parameters:
indexfurniture id
footprintsfurniture footprint information
obstaclesobstacles message in which to store the calculated footprints
isLocalizationtrue if this update is for localization footprints, false if it is for navigation footprints

Definition at line 402 of file furniture_tracker.cpp.

bool FurnitureTracker::getAllPoses ( rail_ceiling::GetAllObstacles::Request &  req,
rail_ceiling::GetAllObstacles::Response &  res 
) [private]

service callback for returning the most recent set of previously published furniture poses

This service allows nodes that subscribe late to the topic to get the furniture poses that were updated before subscribing to the localization layer and navigation layer publishers.

Parameters:
reqservice request denoting whether the request is for localization or navigation obstacle information
resservice response including footprint information

Definition at line 340 of file furniture_tracker.cpp.

void FurnitureTracker::markerCallback ( const ar_track_alvar_msgs::AlvarMarkers::ConstPtr &  msg) [private]

save updated marker data

Parameters:
msgmarker pose data

Definition at line 252 of file furniture_tracker.cpp.

publish localization and navigation data for furniture that has recently changed pose

Furniture poses will be published initially as markers are detected, and subsequently will only be republished if the position exceeds the POSITION_THRESHOLD or if the angle exceeds the ANGULAR_THRESHOLD.

Definition at line 288 of file furniture_tracker.cpp.

void FurnitureTracker::readConfigFiles ( std::string  markerConfigFile,
std::string  furnitureConfigFile 
) [private]

read marker and furniture configuration data

Parameters:
markerConfigFileconfiguration file path for markers on furniture
furnitureConfigFileconfiguration file for localization and navigation furniture footprints

Definition at line 52 of file furniture_tracker.cpp.

bool FurnitureTracker::updated ( geometry_msgs::Pose2D  pose) [private]

determine whether a pose has been updated after its initialization

This function assumes that the pose will never be exactly (0.0, 0.0, 0.0) after it's been updated, which for the purposes of furniture tracking is likely to be accurate.

Parameters:
posethe pose to check
Returns:
true if the pose has been previously updated

Definition at line 430 of file furniture_tracker.cpp.

void FurnitureTracker::updateMessages ( int  index,
std::string  type,
rail_ceiling::Obstacles *  obstacles 
) [private]

update obstacle message data

Parameters:
indexfurniture id
typefurniture type
obstaclesmessage for obstacle information to be used for localization and navigation

Definition at line 377 of file furniture_tracker.cpp.


Member Data Documentation

Definition at line 68 of file furniture_tracker.h.

Definition at line 76 of file furniture_tracker.h.

Definition at line 67 of file furniture_tracker.h.

Definition at line 75 of file furniture_tracker.h.

std::vector<geometry_msgs::Pose2D> FurnitureTracker::furniturePoses [private]

Definition at line 77 of file furniture_tracker.h.

std::vector<geometry_msgs::Pose2D> FurnitureTracker::lastPublishedPoses [private]

Definition at line 78 of file furniture_tracker.h.

std::vector<Marker> FurnitureTracker::markerList [private]

Definition at line 74 of file furniture_tracker.h.

Definition at line 69 of file furniture_tracker.h.

Definition at line 65 of file furniture_tracker.h.

Definition at line 73 of file furniture_tracker.h.

Definition at line 71 of file furniture_tracker.h.


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


rail_ceiling
Author(s): Russell Toris , David Kent
autogenerated on Sat Jun 8 2019 20:39:22