00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00045 #include <signal.h>
00046 #include <uuid/uuid.h>
00047
00048 #include <ros/ros.h>
00049 #include <bondcpp/bond.h>
00050 #include "nodelet/loader.h"
00051 #include "nodelet/NodeletList.h"
00052 #include "nodelet/NodeletLoad.h"
00053 #include "nodelet/NodeletUnload.h"
00054
00055 std::string genId()
00056 {
00057 uuid_t uuid;
00058 uuid_generate_random(uuid);
00059 char uuid_str[40];
00060 uuid_unparse(uuid, uuid_str);
00061 return std::string(uuid_str);
00062 }
00063
00064 class NodeletArgumentParsing
00065 {
00066 private:
00067 std::string command_;
00068 std::string type_;
00069 std::string name_;
00070 std::string default_name_;
00071 std::string manager_;
00072 std::vector<std::string> local_args_;
00073 bool is_bond_enabled_;
00074
00075 public:
00076
00077 bool
00078 parseArgs(int argc, char** argv)
00079 {
00080 is_bond_enabled_ = true;
00081 std::vector<std::string> non_ros_args;
00082 ros::removeROSArgs (argc, argv, non_ros_args);
00083 size_t used_args = 0;
00084
00085 if (non_ros_args.size() > 1)
00086 command_ = non_ros_args[1];
00087 else
00088 return false;
00089
00090 if (command_ == "load" && non_ros_args.size() > 3)
00091 {
00092 type_ = non_ros_args[2];
00093 manager_ = non_ros_args[3];
00094 used_args = 4;
00095
00096 if (non_ros_args.size() > used_args)
00097 {
00098 if (non_ros_args[used_args] == "--no-bond")
00099 {
00100 is_bond_enabled_ = false;
00101 ++used_args;
00102 }
00103 }
00104 }
00105
00106 if (non_ros_args.size() > 2)
00107 {
00108 if (command_ == "unload")
00109 {
00110 name_ = non_ros_args[2];
00111 manager_ = non_ros_args[3];
00112 used_args = 4;
00113 }
00114 else if (command_ == "standalone")
00115 {
00116 type_ = non_ros_args[2];
00117 printf("type is %s\n", type_.c_str());
00118 used_args = 3;
00119 }
00120 }
00121
00122 if (command_ == "manager")
00123 used_args = 2;
00124
00125 for (size_t i = used_args; i < non_ros_args.size(); i++)
00126 local_args_.push_back(non_ros_args[i]);
00127
00128
00129 if (used_args > 0) return true;
00130 else return false;
00131
00132 };
00133
00134
00135 std::string getCommand () const { return (command_); }
00136 std::string getType () const { return (type_); }
00137 std::string getName () const { return (name_); }
00138 std::string getManager() const { return (manager_); }
00139 bool isBondEnabled() const { return is_bond_enabled_; }
00140
00141 std::vector<std::string> getMyArgv () const {return local_args_;};
00142 std::string getDefaultName()
00143 {
00144 std::string s = type_;
00145 replace(s.begin(), s.end(), '/', '_');
00146 return s;
00147 };
00148
00149 };
00150
00151
00152 class NodeletInterface
00153 {
00154 public:
00156
00157 bool
00158 unloadNodelet (const std::string &name, const std::string &manager)
00159 {
00160 ROS_INFO_STREAM ("Unloading nodelet " << name << " from manager " << manager);
00161
00162 std::string service_name = manager + "/unload_nodelet";
00163
00164 if (!ros::service::exists (service_name, true))
00165 {
00166
00167 ROS_WARN("Couldn't find service %s, perhaps the manager is already shut down",
00168 service_name.c_str());
00169 return (false);
00170 }
00171
00172 ros::ServiceClient client = n_.serviceClient<nodelet::NodeletUnload> (service_name);
00173
00174
00175
00176 nodelet::NodeletUnload srv;
00177 srv.request.name = name;
00178 if (!client.call (srv))
00179 {
00180
00181 if (ros::service::exists(service_name, false))
00182 ROS_FATAL("Service call failed!");
00183 return (false);
00184 }
00185 return (true);
00186 }
00187
00189
00190 bool
00191 loadNodelet (const std::string &name, const std::string &type,
00192 const std::string &manager, const std::vector<std::string> &args,
00193 const std::string &bond_id)
00194 {
00195 ros::M_string remappings = ros::names::getRemappings ();
00196 std::vector<std::string> sources (remappings.size ()), targets (remappings.size ());
00197 ROS_INFO_STREAM ("Loading nodelet " << name << " of type " << type << " to manager " << manager << " with the following remappings:");
00198 int i = 0;
00199 for (ros::M_string::iterator it = remappings.begin (); it != remappings.end (); ++it, ++i)
00200 {
00201 sources[i] = (*it).first;
00202 targets[i] = (*it).second;
00203 ROS_INFO_STREAM (sources[i] << " -> " << targets[i]);
00204 }
00205
00206
00207 XmlRpc::XmlRpcValue param;
00208 std::string node_name = ros::this_node::getName ();
00209 n_.getParam (node_name, param);
00210 n_.setParam (name, param);
00211
00212 std::string service_name = std::string (manager) + "/load_nodelet";
00213
00214
00215 ROS_DEBUG ("Waiting for service %s to be available...", service_name.c_str ());
00216 ros::ServiceClient client = n_.serviceClient<nodelet::NodeletLoad> (service_name);
00217 client.waitForExistence ();
00218
00219
00220 nodelet::NodeletLoad srv;
00221 srv.request.name = std::string (name);
00222 srv.request.type = std::string (type);
00223 srv.request.remap_source_args = sources;
00224 srv.request.remap_target_args = targets;
00225 srv.request.my_argv = args;
00226 srv.request.bond_id = bond_id;
00227 if (!client.call (srv))
00228 {
00229 ROS_FATAL("Service call failed!");
00230 return false;
00231 }
00232 return true;
00233 }
00234 private:
00235 ros::NodeHandle n_;
00236 };
00237
00238 void print_usage(int argc, char** argv)
00239 {
00240 printf("Your usage: \n");
00241 for (int i = 0; i < argc; i++)
00242 printf("%s ", argv[i]);
00243 printf("\nnodelet usage:\n");
00244 printf("nodelet load pkg/Type manager [--no-bond] - Launch a nodelet of type pkg/Type on manager manager\n");
00245 printf("nodelet standalone pkg/Type - Launch a nodelet of type pkg/Type in a standalone node\n");
00246 printf("nodelet unload name manager - Unload a nodelet a nodelet by name from manager\n");
00247 printf("nodelet manager - Launch a nodelet manager node\n");
00248
00249 };
00250
00251 sig_atomic_t volatile request_shutdown = 0;
00252
00253 void
00254 nodeletLoaderSigIntHandler (int sig)
00255 {
00256 request_shutdown = 1;
00257 }
00258
00259
00260 int
00261 main (int argc, char** argv)
00262 {
00263 NodeletArgumentParsing arg_parser;
00264
00265 if (!arg_parser.parseArgs(argc, argv))
00266 {
00267 print_usage(argc, argv);
00268 return (-1);
00269 }
00270 std::string command = arg_parser.getCommand();
00271
00272
00273 if (command == "manager")
00274 {
00275 ros::init (argc, argv, "manager");
00276 nodelet::Loader n;
00277 ros::spin ();
00278 }
00279 else if (command == "standalone")
00280 {
00281 ros::init (argc, argv, arg_parser.getDefaultName());
00282
00283 ros::NodeHandle nh;
00284 nodelet::Loader n(false);
00285 ros::M_string remappings;
00286 std::string nodelet_name = ros::this_node::getName ();
00287 std::string nodelet_type = arg_parser.getType();
00288 n.load(nodelet_name, nodelet_type, remappings, arg_parser.getMyArgv());
00289 ROS_DEBUG("Successfully loaded nodelet of type '%s' into name '%s'\n", nodelet_name.c_str(), nodelet_name.c_str());
00290
00291 ros::spin();
00292 }
00293 else if (command == "load")
00294 {
00295 ros::init (argc, argv, arg_parser.getDefaultName (), ros::init_options::NoSigintHandler);
00296 NodeletInterface ni;
00297 ros::NodeHandle nh;
00298 std::string name = ros::this_node::getName ();
00299 std::string type = arg_parser.getType();
00300 std::string manager = arg_parser.getManager();
00301 std::string bond_id;
00302 if (arg_parser.isBondEnabled())
00303 bond_id = name + "_" + genId();
00304 bond::Bond bond(manager + "/bond", bond_id);
00305 if (!ni.loadNodelet(name, type, manager, arg_parser.getMyArgv(), bond_id))
00306 return -1;
00307
00308 signal (SIGINT, nodeletLoaderSigIntHandler);
00309 if (arg_parser.isBondEnabled())
00310 bond.start();
00311
00312 while (nh.ok ())
00313 {
00314 ros::spinOnce();
00315 if (request_shutdown)
00316 {
00317 if (arg_parser.isBondEnabled())
00318 {
00319 bond.breakBond();
00320
00321 for (int i = 0; i < 10; ++i)
00322 {
00323 ros::spinOnce();
00324 if (bond.waitUntilBroken(ros::Duration(0.1)))
00325 break;
00326 }
00327 }
00328 else
00329 {
00330 ni.unloadNodelet (name, manager);
00331 }
00332 ros::shutdown ();
00333 break;
00334 }
00335 else if (arg_parser.isBondEnabled() && bond.isBroken())
00336 {
00337 ros::shutdown();
00338 break;
00339 }
00340 usleep(100000);
00341 }
00342 }
00343 else if (command == "unload")
00344 {
00345 ros::init (argc, argv, arg_parser.getDefaultName ());
00346 std::string name = arg_parser.getName ();
00347 std::string manager = arg_parser.getManager();
00348 NodeletInterface ni;
00349 if (!ni.unloadNodelet(name, manager))
00350 return -1;
00351 }
00352 else
00353 {
00354 ros::init(argc, argv, "nodelet");
00355 ROS_ERROR("Command %s unknown", command.c_str());
00356 return -1;
00357 }
00358
00359 return (0);
00360 }
00361