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));
97 std::vector<std::string> non_ros_args;
101 if (non_ros_args.size() > 1)
106 if (
command_ ==
"load" && non_ros_args.size() > 3)
108 type_ = non_ros_args[2];
112 if (non_ros_args.size() > used_args)
114 if (non_ros_args[used_args] ==
"--no-bond")
122 else if (
command_ ==
"unload" && non_ros_args.size() > 3)
124 type_ =
"nodelet_unloader";
125 name_ = non_ros_args[2];
129 else if (
command_ ==
"standalone" && non_ros_args.size() > 2)
131 type_ = non_ros_args[2];
132 printf(
"type is %s\n",
type_.c_str());
139 for (
size_t i = used_args; i < non_ros_args.size(); i++)
143 if (used_args > 0)
return true;
159 replace(
s.begin(),
s.end(),
'/',
'_');
174 ROS_INFO_STREAM (
"Unloading nodelet " << name <<
" from manager " << manager);
176 std::string service_name = manager +
"/unload_nodelet";
181 ROS_WARN(
"Couldn't find service %s, perhaps the manager is already shut down",
182 service_name.c_str());
190 nodelet::NodeletUnload srv;
191 srv.request.name = name;
192 if (!client.
call (srv))
196 ROS_FATAL_STREAM(
"Failed to unload nodelet '" << name <<
"` from manager `" << manager <<
"'");
206 const std::string &manager,
const std::vector<std::string> &args,
207 const std::string &bond_id)
210 std::vector<std::string> sources (remappings.size ()), targets (remappings.size ());
211 ROS_INFO_STREAM (
"Loading nodelet " << name <<
" of type " << type <<
" to manager " << manager <<
" with the following remappings:");
213 for (ros::M_string::iterator it = remappings.begin (); it != remappings.end (); ++it, ++i)
215 sources[i] = (*it).first;
216 targets[i] = (*it).second;
226 std::string service_name = std::string (manager) +
"/load_nodelet";
229 bool srv_exists =
false;
230 int timeout_sec = 10;
231 int timeout_count = 0;
232 ROS_DEBUG (
"Waiting for service %s to be available...", service_name.c_str ());
234 while (!srv_exists) {
235 if (timeout_count > 0) {
236 ROS_WARN (
"Waiting for service %s to be available for %d seconds...", service_name.c_str (), timeout_count * timeout_sec);
245 nodelet::NodeletLoad srv;
246 srv.request.name = std::string (name);
247 srv.request.type = std::string (type);
248 srv.request.remap_source_args = sources;
249 srv.request.remap_target_args = targets;
250 srv.request.my_argv = args;
251 srv.request.bond_id = bond_id;
252 if (!client.
call (srv))
254 ROS_FATAL_STREAM(
"Failed to load nodelet '" << name <<
"` of type `" << type <<
"` to manager `" << manager <<
"'");
265 printf(
"Your usage: \n");
266 for (
int i = 0; i < argc; i++)
267 printf(
"%s ", argv[i]);
268 printf(
"\nnodelet usage:\n");
269 printf(
"nodelet load pkg/Type manager [--no-bond] - Launch a nodelet of type pkg/Type on manager manager\n");
270 printf(
"nodelet standalone pkg/Type - Launch a nodelet of type pkg/Type in a standalone node\n");
271 printf(
"nodelet unload name manager - Unload a nodelet by name from manager\n");
272 printf(
"nodelet manager - Launch a nodelet manager node\n");
291 num_params = params.
size();
294 std::string reason = params[1];
295 ROS_WARN(
"Shutdown request received. Reason: [%s]", reason.c_str());
322 else if (
command ==
"standalone")
330 std::string nodelet_type = arg_parser.
getType();
331 if(!n.
load(nodelet_name, nodelet_type, remappings, arg_parser.
getMyArgv()))
334 ROS_DEBUG(
"Successfully loaded nodelet of type '%s' into name '%s'\n", nodelet_name.c_str(), nodelet_name.c_str());
345 std::string type = arg_parser.
getType();
346 std::string manager = arg_parser.
getManager();
349 bond_id = name +
"_" +
genId();
387 std::string name = arg_parser.
getName ();
388 std::string manager = arg_parser.
getManager();