15 #include <boost/function.hpp>    18 #include <zeroconf_msgs/AddListener.h>    19 #include <zeroconf_msgs/RemoveListener.h>    20 #include <zeroconf_msgs/AddService.h>    21 #include <zeroconf_msgs/ListDiscoveredServices.h>    22 #include <zeroconf_msgs/ListPublishedServices.h>    24 #include "../../include/zeroconf_avahi/zeroconf.hpp"    55     if (!zeroconf.is_alive()) {
    56       ROS_WARN_STREAM(
"Zeroconf: aborting node initialisation, avahi client is not alive.");
    66     server_list_discovered_services = nh.
advertiseService(
"list_discovered_services",
    68     server_list_published_services = nh.
advertiseService(
"list_published_services",
    70     pub_new_connections = nh.
advertise<DiscoveredService>(
"new_connections", 10);
    71     pub_lost_connections = nh.
advertise<DiscoveredService>(
"lost_connections", 10);
    79     zeroconf.connect_signal_callbacks(new_connection_signal, old_connection_signal);
    88     if (local_nh.
getParam(
"listeners", value))
    92         ROS_ERROR_STREAM(
"Zeroconf: param variable 'listeners' has malformed type, should be of type array");
    96         for (
int i = 0; i < value.
size(); ++i)
    98           zeroconf.add_listener(value[i]);
   104     if (local_nh.
getParam(
"services", value_services))
   108         ROS_ERROR_STREAM(
"Zeroconf: param variable 'services' has malformed type, should be of type array");
   112         for (
int i = 0; i < value_services.
size(); ++i)
   118                 "Zeroconf: " << i << 
"th element of param variable 'services' has malformed type, should be of type struct");
   121           zeroconf_msgs::PublishedService service;
   125             ROS_ERROR_STREAM(
"Zeroconf: services[" << i << 
"]['name'] has malformed type, should be of type string");
   128           service.name = std::string(value_name);
   129           if (service.name == 
"Ros Master")
   137             ROS_ERROR_STREAM(
"Zeroconf: services[" << i << 
"]['type'] has malformed type, should be of type string");
   140           service.type = std::string(value_type);
   144             ROS_ERROR_STREAM(
"Zeroconf: services[" << i << 
"]['domain'] has malformed type, should be of type string");
   147           service.domain = std::string(value_domain);
   154                 "Zeroconf: services[" << service.name << 
"]['port'] wasn't set, default to ros master's port [" << service.port << 
"]");
   159                 "Zeroconf: services[" << service.name << 
"]['port'] has malformed type, should be of type int");
   164             service.port = value_port;
   169             service.description = 
"";
   173             service.description = std::string(value_description);
   175           zeroconf.add_service(service);
   182   bool add_listener(AddListener::Request &request, AddListener::Response &response)
   184     ROS_DEBUG_STREAM(
"Zeroconf: serving an add_listener call... [" << request.service_type << 
"]");
   185     response.result = zeroconf.add_listener(request.service_type);
   188   bool remove_listener(RemoveListener::Request &request, RemoveListener::Response &response)
   190     ROS_DEBUG_STREAM(
"Zeroconf: serving a remove_listener call... [" << request.service_type << 
"]");
   191     response.result = zeroconf.remove_listener(request.service_type);
   194   bool add_service(AddService::Request &request, AddService::Response &response)
   196     response.result = zeroconf.add_service(request.service);
   199   bool remove_service(AddService::Request &request, AddService::Response &response)
   201     response.result = zeroconf.remove_service(request.service);
   206     ROS_DEBUG_STREAM(
"Zeroconf: serving a list_discovered_services call... [" << request.service_type << 
"]");
   207     zeroconf.list_discovered_services(request.service_type, response.services);
   212     zeroconf.list_published_services(request.service_type, response.services);
   217     pub_new_connections.publish(service);
   221     pub_lost_connections.publish(service);
   234 int main(
int argc, 
char **argv)
   240   zeroconf_node.
init(nh);
 bool remove_service(AddService::Request &request, AddService::Response &response)
 
ROSCPP_DECL uint32_t getPort()
 
void lost_connections(DiscoveredService service)
 
ros::ServiceServer server_remove_service
 
ValueStruct::iterator iterator
 
void new_connections(DiscoveredService service)
 
bool add_service(AddService::Request &request, AddService::Response &response)
 
bool add_listener(AddListener::Request &request, AddListener::Response &response)
 
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
 
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
 
Type const & getType() const 
 
Wraps the library api into a fully functional ros node with ros api. 
 
bool list_discovered_services(ListDiscoveredServices::Request &request, ListDiscoveredServices::Response &response)
 
bool list_published_services(ListPublishedServices::Request &request, ListPublishedServices::Response &response)
 
ros::ServiceServer server_list_published_services
 
boost::function< void(zeroconf_msgs::DiscoveredService)> connection_signal_cb
 
Ros interface to linux's avahi daemon. 
 
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
 
#define ROS_WARN_STREAM(args)
 
#define ROS_DEBUG_STREAM(args)
 
ROSCPP_DECL const std::string & getHost()
 
bool remove_listener(RemoveListener::Request &request, RemoveListener::Response &response)
 
ros::Publisher pub_new_connections
 
bool getParam(const std::string &key, std::string &s) const 
 
int main(int argc, char **argv)
 
#define ROS_ERROR_STREAM(args)
 
void init(ros::NodeHandle &nh)