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


nodelet
Author(s): Tully Foote, Radu Bogdan Rusu
autogenerated on Wed Aug 26 2015 14:56:45