nodelet.cpp
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2010, 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  * $Id$
00035  *
00036  */
00037 
00045 #include <signal.h>
00046 #include <uuid/uuid.h>
00047 
00048 #include <ros/ros.h>
00049 #include <ros/xmlrpc_manager.h>
00050 #include <bondcpp/bond.h>
00051 #include "nodelet/loader.h"
00052 #include "nodelet/NodeletList.h"
00053 #include "nodelet/NodeletLoad.h"
00054 #include "nodelet/NodeletUnload.h"
00055 
00056 std::string genId()
00057 {
00058   uuid_t uuid;
00059   uuid_generate_random(uuid);
00060   char uuid_str[40];
00061   uuid_unparse(uuid, uuid_str);
00062   return std::string(uuid_str);
00063 }
00064 
00065 class NodeletArgumentParsing
00066 {
00067   private:
00068     std::string command_;
00069     std::string type_;
00070     std::string name_;
00071     std::string default_name_;
00072     std::string manager_;
00073     std::vector<std::string> local_args_;
00074     bool is_bond_enabled_;
00075 
00076   public:
00077     //NodeletArgumentParsing() { };
00078     bool
00079       parseArgs(int argc, char** argv)
00080     {
00081       is_bond_enabled_ = true;
00082       std::vector<std::string> non_ros_args;
00083       ros::removeROSArgs (argc, argv, non_ros_args);
00084       size_t used_args = 0;
00085 
00086       if (non_ros_args.size() > 1)
00087         command_ = non_ros_args[1];
00088       else
00089         return false;
00090 
00091       if (command_ == "load" && non_ros_args.size() > 3)
00092       {
00093         type_ = non_ros_args[2];
00094         manager_ = non_ros_args[3];
00095         used_args = 4;
00096 
00097         if (non_ros_args.size() > used_args)
00098         {
00099           if (non_ros_args[used_args] == "--no-bond")
00100           {
00101             is_bond_enabled_ = false;
00102             ++used_args;
00103           }
00104         }
00105       }
00106 
00107       else if (command_ == "unload" && non_ros_args.size() > 3)
00108       {
00109         type_    = "nodelet_unloader";
00110         name_    = non_ros_args[2];
00111         manager_ = non_ros_args[3];
00112         used_args = 4;
00113       }
00114       else if (command_ == "standalone" && non_ros_args.size() > 2)
00115       {
00116         type_ = non_ros_args[2];
00117         printf("type is %s\n", type_.c_str());
00118         used_args = 3;
00119       }
00120 
00121       if (command_ == "manager")
00122         used_args = 2;
00123 
00124       for (size_t i = used_args; i < non_ros_args.size(); i++)
00125         local_args_.push_back(non_ros_args[i]);
00126 
00127 
00128       if (used_args > 0) return true;
00129       else return false;
00130 
00131     };
00132 
00133 
00134     std::string getCommand () const { return (command_); }
00135     std::string getType () const    { return (type_);    }
00136     std::string getName () const    { return (name_);    }
00137     std::string getManager() const  { return (manager_); }
00138     bool isBondEnabled() const { return is_bond_enabled_; }
00139 
00140     std::vector<std::string> getMyArgv () const {return local_args_;};
00141     std::string getDefaultName()
00142     {
00143       std::string s = type_;
00144       replace(s.begin(), s.end(), '/', '_');
00145       return s;
00146     };
00147 
00148 };
00149 
00150 
00151 class NodeletInterface
00152 {
00153   public:
00155 
00156     bool
00157       unloadNodelet (const std::string &name, const std::string &manager)
00158     {
00159       ROS_INFO_STREAM ("Unloading nodelet " << name << " from manager " << manager);
00160 
00161       std::string service_name = manager + "/unload_nodelet";
00162       // Check if the service exists and is available
00163       if (!ros::service::exists (service_name, true))
00164       {
00165         // Probably the manager has shut down already, which is fine
00166         ROS_WARN("Couldn't find service %s, perhaps the manager is already shut down",
00167                  service_name.c_str());
00168         return (false);
00169       }
00170 
00171       ros::ServiceClient client = n_.serviceClient<nodelet::NodeletUnload> (service_name);
00172       //client.waitForExistence ();
00173 
00174       // Call the service
00175       nodelet::NodeletUnload srv;
00176       srv.request.name = name;
00177       if (!client.call (srv))
00178       {
00179         // Maybe service shut down in the meantime, which isn't an error
00180         if (ros::service::exists(service_name, false))
00181           ROS_FATAL_STREAM("Failed to unload nodelet '" << name << "` from manager `" << manager << "'");
00182         return (false);
00183       }
00184       return (true);
00185     }
00186 
00188 
00189     bool
00190       loadNodelet (const std::string &name, const std::string &type,
00191                    const std::string &manager, const std::vector<std::string> &args,
00192                    const std::string &bond_id)
00193     {
00194       ros::M_string remappings = ros::names::getRemappings ();
00195       std::vector<std::string> sources (remappings.size ()), targets (remappings.size ());
00196       ROS_INFO_STREAM ("Loading nodelet " << name << " of type " << type << " to manager " << manager << " with the following remappings:");
00197       int i = 0;
00198       for (ros::M_string::iterator it = remappings.begin (); it != remappings.end (); ++it, ++i)
00199       {
00200         sources[i] = (*it).first;
00201         targets[i] = (*it).second;
00202         ROS_INFO_STREAM (sources[i] << " -> " << targets[i]);
00203       }
00204 
00205       // Get and set the parameters
00206       XmlRpc::XmlRpcValue param;
00207       std::string node_name = ros::this_node::getName ();
00208       n_.getParam (node_name, param);
00209       n_.setParam (name, param);
00210 
00211       std::string service_name = std::string (manager) + "/load_nodelet";
00212 
00213       // Wait until the service is advertised
00214       ROS_DEBUG ("Waiting for service %s to be available...", service_name.c_str ());
00215       ros::ServiceClient client = n_.serviceClient<nodelet::NodeletLoad> (service_name);
00216       client.waitForExistence ();
00217 
00218       // Call the service
00219       nodelet::NodeletLoad srv;
00220       srv.request.name = std::string (name);
00221       srv.request.type = std::string (type);
00222       srv.request.remap_source_args = sources;
00223       srv.request.remap_target_args = targets;
00224       srv.request.my_argv = args;
00225       srv.request.bond_id = bond_id;
00226       if (!client.call (srv))
00227       {
00228         ROS_FATAL_STREAM("Failed to load nodelet '" << name << "` of type `" << type << "` to manager `" << manager << "'");
00229         return false;
00230       }
00231       return true;
00232     }
00233   private:
00234     ros::NodeHandle n_;
00235 };
00236 
00237 void print_usage(int argc, char** argv)
00238 {
00239   printf("Your usage: \n");
00240   for (int i = 0; i < argc; i++)
00241     printf("%s ", argv[i]);
00242   printf("\nnodelet usage:\n");
00243   printf("nodelet load pkg/Type manager [--no-bond]  - Launch a nodelet of type pkg/Type on manager manager\n");
00244   printf("nodelet standalone pkg/Type   - Launch a nodelet of type pkg/Type in a standalone node\n");
00245   printf("nodelet unload name manager   - Unload a nodelet by name from manager\n");
00246   printf("nodelet manager               - Launch a nodelet manager node\n");
00247 
00248 };
00249 
00250 sig_atomic_t volatile request_shutdown = 0;
00251 
00252 void nodeletLoaderSigIntHandler(int)
00253 {
00254   request_shutdown = 1;
00255 }
00256 
00257 // Shutdown can be triggered externally by an XML-RPC call, this is how "rosnode kill"
00258 // works. When shutting down a "nodelet load" we always want to unload the nodelet
00259 // before shutting down our ROS comm channels, so we override the default roscpp
00260 // handler for a "shutdown" XML-RPC call.
00261 void shutdownCallback(XmlRpc::XmlRpcValue& params, XmlRpc::XmlRpcValue& result)
00262 {
00263   int num_params = 0;
00264   if (params.getType() == XmlRpc::XmlRpcValue::TypeArray)
00265     num_params = params.size();
00266   if (num_params > 1)
00267   {
00268     std::string reason = params[1];
00269     ROS_WARN("Shutdown request received. Reason: [%s]", reason.c_str());
00270     request_shutdown = 1;
00271   }
00272 
00273   result = ros::xmlrpc::responseInt(1, "", 0);
00274 }
00275 
00276 /* ---[ */
00277 int
00278   main (int argc, char** argv)
00279 {
00280   NodeletArgumentParsing arg_parser;
00281 
00282   if (!arg_parser.parseArgs(argc, argv))
00283   {
00284     print_usage(argc, argv);
00285     return (-1);
00286   }
00287   std::string command = arg_parser.getCommand();
00288 
00289 
00290   if (command == "manager")
00291   {
00292     ros::init (argc, argv, "manager");
00293     nodelet::Loader n;
00294     ros::spin ();
00295   }
00296   else if (command == "standalone")
00297   {
00298     ros::init (argc, argv, arg_parser.getDefaultName());
00299 
00300     ros::NodeHandle nh;
00301     nodelet::Loader n(false);
00302     ros::M_string remappings; //Remappings are already applied by ROS no need to generate them.
00303     std::string nodelet_name = ros::this_node::getName ();
00304     std::string nodelet_type = arg_parser.getType();
00305     if(!n.load(nodelet_name, nodelet_type, remappings, arg_parser.getMyArgv()))
00306       return -1;
00307 
00308     ROS_DEBUG("Successfully loaded nodelet of type '%s' into name '%s'\n", nodelet_name.c_str(), nodelet_name.c_str());
00309 
00310     ros::spin();
00311   }
00312   else if (command == "load")
00313   {
00314     ros::init (argc, argv, arg_parser.getDefaultName (), ros::init_options::NoSigintHandler);
00315     NodeletInterface ni;
00316     ros::NodeHandle nh;
00317     std::string name = ros::this_node::getName ();
00318     std::string type = arg_parser.getType();
00319     std::string manager = arg_parser.getManager();
00320     std::string bond_id;
00321     if (arg_parser.isBondEnabled())
00322       bond_id = name + "_" + genId();
00323     bond::Bond bond(manager + "/bond", bond_id);
00324     if (!ni.loadNodelet(name, type, manager, arg_parser.getMyArgv(), bond_id))
00325       return -1;
00326 
00327     // Override default exit handlers for roscpp
00328     signal(SIGINT, nodeletLoaderSigIntHandler);
00329     ros::XMLRPCManager::instance()->unbind("shutdown");
00330     ros::XMLRPCManager::instance()->bind("shutdown", shutdownCallback);
00331 
00332     if (arg_parser.isBondEnabled())
00333       bond.start();
00334     // Spin our own loop
00335     ros::AsyncSpinner spinner(1);
00336     spinner.start();
00337     while (!request_shutdown)
00338     {
00339       if (arg_parser.isBondEnabled() && bond.isBroken())
00340       {
00341         ROS_INFO("Bond broken, exiting");
00342         goto shutdown;
00343       }
00344       usleep(100000);
00345     }
00346     // Attempt to unload the nodelet before shutting down ROS
00347     ni.unloadNodelet(name, manager);
00348     if (arg_parser.isBondEnabled())
00349       bond.breakBond();
00350   shutdown:
00351     ros::shutdown();
00352   }
00353   else if (command == "unload")
00354   {
00355     ros::init (argc, argv, arg_parser.getDefaultName ());
00356     std::string name = arg_parser.getName ();
00357     std::string manager = arg_parser.getManager();
00358     NodeletInterface ni;
00359     if (!ni.unloadNodelet(name, manager))
00360       return -1;
00361   }
00362   else
00363   {
00364     ros::init(argc, argv, "nodelet");
00365     ROS_ERROR("Command %s unknown", command.c_str());
00366     return -1;
00367   }
00368 
00369   return (0);
00370 }
00371 /* ]--- */


nodelet
Author(s): Tully Foote, Radu Bogdan Rusu
autogenerated on Sun Aug 6 2017 02:23:55