51 #include "nodelet/NodeletList.h"
52 #include "nodelet/NodeletLoad.h"
53 #include "nodelet/NodeletUnload.h"
56 # include <uuid/uuid.h>
65 uuid_generate_random(uuid);
67 uuid_unparse(uuid, uuid_str);
68 return std::string(uuid_str);
73 UuidToStringA(&uuid, &str);
74 std::string return_string(
reinterpret_cast<char *
>(str));
96 std::vector<std::string> non_ros_args;
100 if (non_ros_args.size() > 1)
105 if (
command_ ==
"load" && non_ros_args.size() > 3)
107 type_ = non_ros_args[2];
111 if (non_ros_args.size() > used_args)
113 if (non_ros_args[used_args] ==
"--no-bond")
121 else if (
command_ ==
"unload" && non_ros_args.size() > 3)
123 type_ =
"nodelet_unloader";
124 name_ = non_ros_args[2];
128 else if (
command_ ==
"standalone" && non_ros_args.size() > 2)
130 type_ = non_ros_args[2];
131 printf(
"type is %s\n",
type_.c_str());
138 for (
size_t i = used_args; i < non_ros_args.size(); i++)
142 if (used_args > 0)
return true;
158 replace(
s.begin(),
s.end(),
'/',
'_');
173 ROS_INFO_STREAM (
"Unloading nodelet " << name <<
" from manager " << manager);
175 std::string service_name = manager +
"/unload_nodelet";
180 ROS_WARN(
"Couldn't find service %s, perhaps the manager is already shut down",
181 service_name.c_str());
189 nodelet::NodeletUnload srv;
190 srv.request.name = name;
191 if (!client.
call (srv))
195 ROS_FATAL_STREAM(
"Failed to unload nodelet '" << name <<
"` from manager `" << manager <<
"'");
205 const std::string &manager,
const std::vector<std::string> &args,
206 const std::string &bond_id)
209 std::vector<std::string> sources (remappings.size ()), targets (remappings.size ());
210 ROS_INFO_STREAM (
"Loading nodelet " << name <<
" of type " << type <<
" to manager " << manager <<
" with the following remappings:");
212 for (ros::M_string::iterator it = remappings.begin (); it != remappings.end (); ++it, ++i)
214 sources[i] = (*it).first;
215 targets[i] = (*it).second;
225 std::string service_name = std::string (manager) +
"/load_nodelet";
228 bool srv_exists =
false;
229 int timeout_sec = 10;
230 int timeout_count = 0;
231 ROS_DEBUG (
"Waiting for service %s to be available...", service_name.c_str ());
233 while (!srv_exists) {
234 if (timeout_count > 0) {
235 ROS_WARN (
"Waiting for service %s to be available for %d seconds...", service_name.c_str (), timeout_count * timeout_sec);
244 nodelet::NodeletLoad srv;
245 srv.request.name = std::string (name);
246 srv.request.type = std::string (type);
247 srv.request.remap_source_args = sources;
248 srv.request.remap_target_args = targets;
249 srv.request.my_argv = args;
250 srv.request.bond_id = bond_id;
251 if (!client.
call (srv))
253 ROS_FATAL_STREAM(
"Failed to load nodelet '" << name <<
"` of type `" << type <<
"` to manager `" << manager <<
"'");
264 printf(
"Your usage: \n");
265 for (
int i = 0; i < argc; i++)
266 printf(
"%s ", argv[i]);
267 printf(
"\nnodelet usage:\n");
268 printf(
"nodelet load pkg/Type manager [--no-bond] - Launch a nodelet of type pkg/Type on manager manager\n");
269 printf(
"nodelet standalone pkg/Type - Launch a nodelet of type pkg/Type in a standalone node\n");
270 printf(
"nodelet unload name manager - Unload a nodelet by name from manager\n");
271 printf(
"nodelet manager - Launch a nodelet manager node\n");
290 num_params = params.
size();
293 std::string reason = params[1];
294 ROS_WARN(
"Shutdown request received. Reason: [%s]", reason.c_str());
321 else if (
command ==
"standalone")
329 std::string nodelet_type = arg_parser.
getType();
330 if(!n.
load(nodelet_name, nodelet_type, remappings, arg_parser.
getMyArgv()))
333 ROS_DEBUG(
"Successfully loaded nodelet of type '%s' into name '%s'\n", nodelet_name.c_str(), nodelet_name.c_str());
344 std::string type = arg_parser.
getType();
345 std::string manager = arg_parser.
getManager();
348 bond_id = name +
"_" +
genId();
386 std::string name = arg_parser.
getName ();
387 std::string manager = arg_parser.
getManager();