service_client_link.cpp
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2008, Willow Garage, Inc.
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of Willow Garage, Inc. nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  */
00034 
00035 #include "ros/service_client_link.h"
00036 #include "ros/service_publication.h"
00037 #include "ros/header.h"
00038 #include "ros/connection.h"
00039 #include "ros/service_manager.h"
00040 #include "ros/transport/transport.h"
00041 #include "ros/this_node.h"
00042 #include "ros/file_log.h"
00043 
00044 #include <boost/bind.hpp>
00045 
00046 namespace ros
00047 {
00048 
00049 ServiceClientLink::ServiceClientLink()
00050 : persistent_(false)
00051 {
00052 }
00053 
00054 ServiceClientLink::~ServiceClientLink()
00055 {
00056   if (connection_)
00057   {
00058     if (connection_->isSendingHeaderError())
00059     {
00060       connection_->removeDropListener(dropped_conn_);
00061     }
00062     else
00063     {
00064       connection_->drop(Connection::Destructing);
00065     }
00066   }
00067 }
00068 
00069 bool ServiceClientLink::initialize(const ConnectionPtr& connection)
00070 {
00071   connection_ = connection;
00072   dropped_conn_ = connection_->addDropListener(boost::bind(&ServiceClientLink::onConnectionDropped, this, _1));
00073 
00074   return true;
00075 }
00076 
00077 bool ServiceClientLink::handleHeader(const Header& header)
00078 {
00079   std::string md5sum, service, client_callerid;
00080   if (!header.getValue("md5sum", md5sum)
00081    || !header.getValue("service", service)
00082    || !header.getValue("callerid", client_callerid))
00083   {
00084     std::string msg("bogus tcpros header. did not have the "
00085                           "required elements: md5sum, service, callerid");
00086 
00087     ROS_ERROR("%s", msg.c_str());
00088     connection_->sendHeaderError(msg);
00089 
00090     return false;
00091   }
00092 
00093   std::string persistent;
00094   if (header.getValue("persistent", persistent))
00095   {
00096     if (persistent == "1" || persistent == "true")
00097     {
00098       persistent_ = true;
00099     }
00100   }
00101 
00102   ROSCPP_LOG_DEBUG("Service client [%s] wants service [%s] with md5sum [%s]", client_callerid.c_str(), service.c_str(), md5sum.c_str());
00103   ServicePublicationPtr ss = ServiceManager::instance()->lookupServicePublication(service);
00104   if (!ss)
00105   {
00106     std::string msg = std::string("received a tcpros connection for a "
00107                              "nonexistent service [") +
00108             service + std::string("].");
00109 
00110     ROS_ERROR("%s", msg.c_str());
00111     connection_->sendHeaderError(msg);
00112 
00113     return false;
00114   }
00115   if (ss->getMD5Sum() != md5sum &&
00116       (md5sum != std::string("*") && ss->getMD5Sum() != std::string("*")))
00117   {
00118     std::string msg = std::string("client wants service ") + service +
00119             std::string(" to have md5sum ") + md5sum +
00120             std::string(", but it has ") + ss->getMD5Sum() +
00121             std::string(". Dropping connection.");
00122 
00123     ROS_ERROR("%s", msg.c_str());
00124     connection_->sendHeaderError(msg);
00125 
00126     return false;
00127   }
00128 
00129   // Check whether the service (ss here) has been deleted from
00130   // advertised_topics through a call to unadvertise(), which could
00131   // have happened while we were waiting for the subscriber to
00132   // provide the md5sum.
00133   if(ss->isDropped())
00134   {
00135     std::string msg = std::string("received a tcpros connection for a "
00136                              "nonexistent service [") +
00137             service + std::string("].");
00138 
00139     ROS_ERROR("%s", msg.c_str());
00140     connection_->sendHeaderError(msg);
00141 
00142     return false;
00143   }
00144   else
00145   {
00146     parent_ = ServicePublicationWPtr(ss);
00147 
00148     // Send back a success, with info
00149     M_string m;
00150     m["request_type"] = ss->getRequestDataType();
00151     m["response_type"] = ss->getResponseDataType();
00152     m["type"] = ss->getDataType();
00153     m["md5sum"] = ss->getMD5Sum();
00154     m["callerid"] = this_node::getName();
00155     connection_->writeHeader(m, boost::bind(&ServiceClientLink::onHeaderWritten, this, _1));
00156 
00157     ss->addServiceClientLink(shared_from_this());
00158   }
00159 
00160   return true;
00161 }
00162 
00163 void ServiceClientLink::onConnectionDropped(const ConnectionPtr& conn)
00164 {
00165   ROS_ASSERT(conn == connection_);
00166 
00167   if (ServicePublicationPtr parent = parent_.lock())
00168   {
00169     parent->removeServiceClientLink(shared_from_this());
00170   }
00171 }
00172 
00173 void ServiceClientLink::onHeaderWritten(const ConnectionPtr& conn)
00174 {
00175   connection_->read(4, boost::bind(&ServiceClientLink::onRequestLength, this, _1, _2, _3, _4));
00176 }
00177 
00178 void ServiceClientLink::onRequestLength(const ConnectionPtr& conn, const boost::shared_array<uint8_t>& buffer, uint32_t size, bool success)
00179 {
00180   if (!success)
00181     return;
00182 
00183   ROS_ASSERT(conn == connection_);
00184   ROS_ASSERT(size == 4);
00185 
00186   uint32_t len = *((uint32_t*)buffer.get());
00187 
00188   if (len > 1000000000)
00189   {
00190     ROS_ERROR("a message of over a gigabyte was " \
00191                 "predicted in tcpros. that seems highly " \
00192                 "unlikely, so I'll assume protocol " \
00193                 "synchronization is lost.");
00194     conn->drop(Connection::Destructing);
00195     return;
00196   }
00197 
00198   connection_->read(len, boost::bind(&ServiceClientLink::onRequest, this, _1, _2, _3, _4));
00199 }
00200 
00201 void ServiceClientLink::onRequest(const ConnectionPtr& conn, const boost::shared_array<uint8_t>& buffer, uint32_t size, bool success)
00202 {
00203   if (!success)
00204     return;
00205 
00206   ROS_ASSERT(conn == connection_);
00207 
00208   if (ServicePublicationPtr parent = parent_.lock())
00209   {
00210     parent->processRequest(buffer, size, shared_from_this());
00211   }
00212   else
00213   {
00214     ROS_BREAK();
00215   }
00216 }
00217 
00218 void ServiceClientLink::onResponseWritten(const ConnectionPtr& conn)
00219 {
00220   ROS_ASSERT(conn == connection_);
00221 
00222   if (persistent_)
00223   {
00224     connection_->read(4, boost::bind(&ServiceClientLink::onRequestLength, this, _1, _2, _3, _4));
00225   }
00226   else
00227   {
00228     connection_->drop(Connection::Destructing);
00229   }
00230 }
00231 
00232 void ServiceClientLink::processResponse(bool ok, const SerializedMessage& res)
00233 {
00234   connection_->write(res.buf, res.num_bytes, boost::bind(&ServiceClientLink::onResponseWritten, this, _1));
00235 }
00236 
00237 
00238 } // namespace ros
00239 


roscpp
Author(s): Morgan Quigley, Josh Faust, Brian Gerkey, Troy Straszheim
autogenerated on Fri Aug 28 2015 12:33:11