#include <RosLoService.h>

| Classes | |
| class | PubParentFilterStruct | 
| Public Member Functions | |
| bool | CallbackRegisterService (vision_srvs::register_jlo_callback::Request &request, vision_srvs::register_jlo_callback::Response &answer) | 
| bool | PublishUpdate (unsigned long id, PubParentFilterStruct &obj_to_pub) | 
| Helper fundction handling the final publishing of updated registered jlos. | |
| RosLoService (const char *nodename, ros::NodeHandle &n, std::string configFile) | |
| bool | ServiceCallback (vision_srvs::srvjlo::Request &request, vision_srvs::srvjlo::Response &answer) | 
| void | UpdateEventHandler () | 
| this function will wait for update events and publish then a partial lo to specified topics | |
| ~RosLoService () | |
| Static Public Member Functions | |
| static void | UpdateEventNotifier (unsigned long object_id) | 
| raises and update event | |
| Private Member Functions | |
| void | tf_subscription_callback (const tf::tfMessage::ConstPtr &msg_in_) | 
| Private Attributes | |
| ros::ServiceServer | located_object_service | 
| std::map< unsigned long, PubParentFilterStruct > | m_jlotopicMap | 
| std::map< unsigned long, unsigned long > | m_parentToRegisteredJlo | 
| std::map< std::string, ros::Publisher > | m_topicPublisherMap | 
| std::set< std::string > | tf_blacklist | 
| ros::Subscriber | tf_subscription | 
| Static Private Attributes | |
| static std::queue< unsigned long > | m_queueOfLosToPublish | 
Jennifer's Located Object Copyright (C) 2008, U. Klank
This program is free software: you can redistribute it and/or modify it under the terms of the GNU General Public License as published by the Free Software Foundation, either version 3 of the License, or (at your option) any later version.
This program is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for more details.
You should have received a copy of the GNU General Public License along with this program. If not, see <http://www.gnu.org/licenses/>. class RosLoService Implementation for ros calling the lo-ServiceInterface functionality
Definition at line 42 of file RosLoService.h.
| RosLoService::RosLoService | ( | const char * | nodename, | 
| ros::NodeHandle & | n, | ||
| std::string | configFile | ||
| ) | 
Start the service listening to listeningTopic, g_stopAll can stop the loop after next read
Advertise the service that answers to normal lo-quieries
Subscribe to a tf topic and listening to it.
Definition at line 48 of file RosLoService.cpp.
Closing of the ports
Definition at line 94 of file RosLoService.cpp.
| bool RosLoService::CallbackRegisterService | ( | vision_srvs::register_jlo_callback::Request & | request, | 
| vision_srvs::register_jlo_callback::Response & | answer | ||
| ) | 
Register a callback that wil publish any change on a certain lo id
| request | incoming request: topicname and id | 
| answer | outgoing answer: error | 
Definition at line 548 of file RosLoService.cpp.
| bool RosLoService::PublishUpdate | ( | unsigned long | id, | 
| PubParentFilterStruct & | obj_to_pub | ||
| ) | 
Helper fundction handling the final publishing of updated registered jlos.
PublishUpdate
| id | jlo to be published | 
| obj_to_pub | object containing parent id and list of publishers to which the update will be send | 
| return | false if the referenced jlo was already deleted | 
apply filter
Definition at line 425 of file RosLoService.cpp.
| bool RosLoService::ServiceCallback | ( | vision_srvs::srvjlo::Request & | request, | 
| vision_srvs::srvjlo::Response & | answer | ||
| ) | 
Parses a service request and reacts on the input, by generating the answer
| request | incoming request: command := {idquery, framequery, update, del, cout}, [id|parentid|matrix, cov,type|name]+ | 
| answer | outgoing answer: error, [id, parentid, matrix, cov, type, name] | 
Definition at line 163 of file RosLoService.cpp.
| void RosLoService::tf_subscription_callback | ( | const tf::tfMessage::ConstPtr & | msg_in_ | ) |  [private] | 
subscribing to one tf topic to update lowlevel entries
Definition at line 582 of file RosLoService.cpp.
| void RosLoService::UpdateEventHandler | ( | ) | 
this function will wait for update events and publish then a partial lo to specified topics
UpdateEventHandler
register all parents and map them back to updates of children
Definition at line 500 of file RosLoService.cpp.
| void RosLoService::UpdateEventNotifier | ( | unsigned long | object_id | ) |  [static] | 
Definition at line 107 of file RosLoService.h.
| std::map<unsigned long, PubParentFilterStruct > RosLoService::m_jlotopicMap  [private] | 
Handle call
Definition at line 115 of file RosLoService.h.
| std::map<unsigned long, unsigned long> RosLoService::m_parentToRegisteredJlo  [private] | 
Definition at line 116 of file RosLoService.h.
| std::queue< unsigned long > RosLoService::m_queueOfLosToPublish  [static, private] | 
Definition at line 118 of file RosLoService.h.
| std::map<std::string, ros::Publisher> RosLoService::m_topicPublisherMap  [private] | 
Definition at line 117 of file RosLoService.h.
| std::set<std::string> RosLoService::tf_blacklist  [private] | 
Definition at line 108 of file RosLoService.h.
| ros::Subscriber RosLoService::tf_subscription  [private] | 
Members to handle tf subscription and main service
Definition at line 106 of file RosLoService.h.