#include <furniture_tracker.h>
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< FurnitureTransforms > | footprintTransforms |
ros::Publisher | furnitureLayerPub |
std::vector< Furniture > | furnitureList |
std::vector < geometry_msgs::Pose2D > | furniturePoses |
std::vector < geometry_msgs::Pose2D > | lastPublishedPoses |
std::vector< Marker > | markerList |
std::vector< ros::Subscriber > | markerSubscribers |
ros::NodeHandle | n |
bool | readInitialPoses |
tf::TransformListener | tfListener |
Definition at line 48 of file furniture_tracker.h.
Constructor, initializes data structures containing information about markers and furniture obstacles.
Definition at line 15 of file furniture_tracker.cpp.
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.
index | furniture id |
footprints | furniture footprint information |
obstacles | obstacles message in which to store the calculated footprints |
isLocalization | true 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.
req | service request denoting whether the request is for localization or navigation obstacle information |
res | service 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
msg | marker 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
markerConfigFile | configuration file path for markers on furniture |
furnitureConfigFile | configuration 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.
pose | the pose to check |
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
index | furniture id |
type | furniture type |
obstacles | message for obstacle information to be used for localization and navigation |
Definition at line 377 of file furniture_tracker.cpp.
Definition at line 68 of file furniture_tracker.h.
std::vector<FurnitureTransforms> FurnitureTracker::footprintTransforms [private] |
Definition at line 76 of file furniture_tracker.h.
Definition at line 67 of file furniture_tracker.h.
std::vector<Furniture> FurnitureTracker::furnitureList [private] |
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.
std::vector<ros::Subscriber> FurnitureTracker::markerSubscribers [private] |
Definition at line 69 of file furniture_tracker.h.
ros::NodeHandle FurnitureTracker::n [private] |
Definition at line 65 of file furniture_tracker.h.
bool FurnitureTracker::readInitialPoses [private] |
Definition at line 73 of file furniture_tracker.h.
Definition at line 71 of file furniture_tracker.h.