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
00074 public:
00075
00076 bool
00077 parseArgs(int argc, char** argv)
00078 {
00079 std::vector<std::string> non_ros_args;
00080 ros::removeROSArgs (argc, argv, non_ros_args);
00081 size_t used_args = 0;
00082
00083 if (non_ros_args.size() > 1)
00084 command_ = non_ros_args[1];
00085 else
00086 return false;
00087
00088 if (command_ == "load" && non_ros_args.size() > 3)
00089 {
00090 type_ = non_ros_args[2];
00091 manager_ = non_ros_args[3];
00092 used_args = 4;
00093 }
00094
00095 if (non_ros_args.size() > 2)
00096 {
00097 if (command_ == "unload")
00098 {
00099 name_ = non_ros_args[2];
00100 manager_ = non_ros_args[3];
00101 used_args = 4;
00102 }
00103 else if (command_ == "standalone")
00104 {
00105 type_ = non_ros_args[2];
00106 printf("type is %s\n", type_.c_str());
00107 used_args = 3;
00108 }
00109 }
00110
00111 if (command_ == "manager")
00112 used_args = 2;
00113
00114 for (size_t i = used_args; i < non_ros_args.size(); i++)
00115 local_args_.push_back(non_ros_args[i]);
00116
00117
00118 if (used_args > 0) return true;
00119 else return false;
00120
00121 };
00122
00123
00124 std::string getCommand () const { return (command_); }
00125 std::string getType () const { return (type_); }
00126 std::string getName () const { return (name_); }
00127 std::string getManager() const { return (manager_); }
00128
00129 std::vector<std::string> getMyArgv () const {return local_args_;};
00130 std::string getDefaultName()
00131 {
00132 std::string s = type_;
00133 replace(s.begin(), s.end(), '/', '_');
00134 return s;
00135 };
00136
00137 };
00138
00139
00140 class NodeletInterface
00141 {
00142 public:
00144
00145 bool
00146 unloadNodelet (const std::string &name, const std::string &manager)
00147 {
00148 ROS_INFO_STREAM ("Unloading nodelet " << name << " from manager " << manager);
00149
00150 std::string service_name = manager + "/unload_nodelet";
00151
00152 if (!ros::service::exists (service_name, true))
00153 return (false);
00154
00155
00156 ros::ServiceClient client = n_.serviceClient<nodelet::NodeletUnload> (service_name);
00157
00158
00159
00160 nodelet::NodeletUnload srv;
00161 srv.request.name = name;
00162 if (!client.call (srv))
00163 {
00164
00165 return (false);
00166 }
00167 return (true);
00168 }
00169
00171
00172 bool
00173 loadNodelet (const std::string &name, const std::string &type,
00174 const std::string &manager, const std::vector<std::string> &args,
00175 const std::string &bond_id)
00176 {
00177 ros::M_string remappings = ros::names::getRemappings ();
00178 std::vector<std::string> sources (remappings.size ()), targets (remappings.size ());
00179 ROS_INFO_STREAM ("Loading nodelet " << name << " of type " << type << " to manager " << manager << " with the following remappings:");
00180 int i = 0;
00181 for (ros::M_string::iterator it = remappings.begin (); it != remappings.end (); ++it, ++i)
00182 {
00183 sources[i] = (*it).first;
00184 targets[i] = (*it).second;
00185 ROS_INFO_STREAM (sources[i] << " -> " << targets[i]);
00186 }
00187
00188
00189 XmlRpc::XmlRpcValue param;
00190 std::string node_name = ros::this_node::getName ();
00191 n_.getParam (node_name, param);
00192 n_.setParam (name, param);
00193
00194 std::string service_name = std::string (manager) + "/load_nodelet";
00195
00196
00197 ROS_DEBUG ("Waiting for service %s to be available...", service_name.c_str ());
00198 ros::ServiceClient client = n_.serviceClient<nodelet::NodeletLoad> (service_name);
00199 client.waitForExistence ();
00200
00201
00202 nodelet::NodeletLoad srv;
00203 srv.request.name = std::string (name);
00204 srv.request.type = std::string (type);
00205 srv.request.remap_source_args = sources;
00206 srv.request.remap_target_args = targets;
00207 srv.request.my_argv = args;
00208 srv.request.bond_id = bond_id;
00209 if (!client.call (srv))
00210 {
00211
00212 return false;
00213 }
00214 return true;
00215 }
00216 private:
00217 ros::NodeHandle n_;
00218 };
00219
00220 void print_usage(int argc, char** argv)
00221 {
00222 printf("Your usage: \n");
00223 for (int i = 0; i < argc; i++)
00224 printf("%s ", argv[i]);
00225 printf("\nnodelet usage:\n");
00226 printf("nodelet load pkg/Type manager - Launch a nodelet of type pkg/Type on manager manager\n");
00227 printf("nodelet standalone pkg/Type - Launch a nodelet of type pkg/Type in a standalone node\n");
00228 printf("nodelet unload name manager - Unload a nodelet a nodelet by name from manager\n");
00229 printf("nodelet manager - Launch a nodelet manager node\n");
00230
00231 };
00232
00233 sig_atomic_t volatile request_shutdown = 0;
00234
00235 void
00236 nodeletLoaderSigIntHandler (int sig)
00237 {
00238 request_shutdown = 1;
00239 }
00240
00241
00242 int
00243 main (int argc, char** argv)
00244 {
00245 NodeletArgumentParsing arg_parser;
00246
00247 if (!arg_parser.parseArgs(argc, argv))
00248 {
00249 print_usage(argc, argv);
00250 return (-1);
00251 }
00252 std::string command = arg_parser.getCommand();
00253
00254
00255 if (command == "manager")
00256 {
00257 ros::init (argc, argv, "manager");
00258 nodelet::Loader n;
00259 ros::spin ();
00260 }
00261 else if (command == "standalone")
00262 {
00263 ros::init (argc, argv, arg_parser.getDefaultName());
00264
00265 nodelet::Loader n(false);
00266 ros::NodeHandle nh;
00267 ros::M_string remappings;
00268 std::string nodelet_name = ros::this_node::getName ();
00269 std::string nodelet_type = arg_parser.getType();
00270 n.load(nodelet_name, nodelet_type, remappings, arg_parser.getMyArgv());
00271 ROS_DEBUG("Successfully loaded nodelet of type '%s' into name '%s'\n", nodelet_name.c_str(), nodelet_name.c_str());
00272
00273 ros::spin();
00274 }
00275 else if (command == "load")
00276 {
00277 ros::init (argc, argv, arg_parser.getDefaultName (), ros::init_options::NoSigintHandler);
00278 NodeletInterface ni;
00279 ros::NodeHandle nh;
00280 std::string name = ros::this_node::getName ();
00281 std::string type = arg_parser.getType();
00282 std::string manager = arg_parser.getManager();
00283 std::string bond_id = name + "_" + genId();
00284 bond::Bond bond(manager + "/bond", bond_id);
00285 ni.loadNodelet (name, type, manager, arg_parser.getMyArgv(), bond_id);
00286 signal (SIGINT, nodeletLoaderSigIntHandler);
00287 bond.start();
00288
00289 while (nh.ok ())
00290 {
00291 ros::spinOnce();
00292 if (request_shutdown)
00293 {
00294 bond.breakBond();
00295
00296 for (int i = 0; i < 10; ++i)
00297 {
00298 ros::spinOnce();
00299 if (bond.waitUntilBroken(ros::Duration(0.1)))
00300 break;
00301 }
00302
00303 ros::shutdown ();
00304 break;
00305 }
00306 else if (bond.isBroken())
00307 {
00308 ros::shutdown();
00309 break;
00310 }
00311 usleep(100000);
00312 }
00313 }
00314 else if (command == "unload")
00315 {
00316 ros::init (argc, argv, arg_parser.getDefaultName ());
00317 std::string name = arg_parser.getName ();
00318 std::string manager = arg_parser.getManager();
00319 NodeletInterface ni;
00320 ni.unloadNodelet (name, manager);
00321 }
00322 else
00323 {
00324 ros::init(argc, argv, "nodelet");
00325 ROS_ERROR("Command %s unknown", command.c_str());
00326 return -1;
00327 }
00328
00329 return (0);
00330 }
00331