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 is_bond_enabled_ =
true;
97 std::vector<std::string> non_ros_args;
101 if (non_ros_args.size() > 1)
102 command_ = non_ros_args[1];
106 if (command_ ==
"load" && non_ros_args.size() > 3)
108 type_ = non_ros_args[2];
109 manager_ = non_ros_args[3];
112 if (non_ros_args.size() > used_args)
114 if (non_ros_args[used_args] ==
"--no-bond")
116 is_bond_enabled_ =
false;
122 else if (command_ ==
"unload" && non_ros_args.size() > 3)
124 type_ =
"nodelet_unloader";
125 name_ = non_ros_args[2];
126 manager_ = non_ros_args[3];
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());
136 if (command_ ==
"manager")
139 for (
size_t i = used_args; i < non_ros_args.size(); i++)
140 local_args_.push_back(non_ros_args[i]);
143 if (used_args > 0)
return true;
150 std::string
getType ()
const {
return (type_); }
151 std::string
getName ()
const {
return (name_); }
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;
217 ROS_INFO_STREAM (sources[i] <<
" -> " << targets[i]);
223 n_.getParam (node_name, param);
224 n_.setParam (name, param);
226 std::string service_name = std::string (manager) +
"/load_nodelet";
229 ROS_DEBUG (
"Waiting for service %s to be available...", service_name.c_str ());
231 client.waitForExistence ();
234 nodelet::NodeletLoad srv;
235 srv.request.name = std::string (name);
236 srv.request.type = std::string (type);
237 srv.request.remap_source_args = sources;
238 srv.request.remap_target_args = targets;
239 srv.request.my_argv = args;
240 srv.request.bond_id = bond_id;
241 if (!client.call (srv))
243 ROS_FATAL_STREAM(
"Failed to load nodelet '" << name <<
"` of type `" << type <<
"` to manager `" << manager <<
"'");
254 printf(
"Your usage: \n");
255 for (
int i = 0; i < argc; i++)
256 printf(
"%s ", argv[i]);
257 printf(
"\nnodelet usage:\n");
258 printf(
"nodelet load pkg/Type manager [--no-bond] - Launch a nodelet of type pkg/Type on manager manager\n");
259 printf(
"nodelet standalone pkg/Type - Launch a nodelet of type pkg/Type in a standalone node\n");
260 printf(
"nodelet unload name manager - Unload a nodelet by name from manager\n");
261 printf(
"nodelet manager - Launch a nodelet manager node\n");
280 num_params = params.
size();
283 std::string reason = params[1];
284 ROS_WARN(
"Shutdown request received. Reason: [%s]", reason.c_str());
305 if (command ==
"manager")
311 else if (command ==
"standalone")
319 std::string nodelet_type = arg_parser.
getType();
320 if(!n.
load(nodelet_name, nodelet_type, remappings, arg_parser.
getMyArgv()))
323 ROS_DEBUG(
"Successfully loaded nodelet of type '%s' into name '%s'\n", nodelet_name.c_str(), nodelet_name.c_str());
327 else if (command ==
"load")
333 std::string type = arg_parser.
getType();
334 std::string manager = arg_parser.
getManager();
337 bond_id = name +
"_" +
genId();
339 if (!ni.loadNodelet(name, type, manager, arg_parser.
getMyArgv(), bond_id))
366 ni.unloadNodelet(name, manager);
372 else if (command ==
"unload")
375 std::string name = arg_parser.
getName ();
376 std::string manager = arg_parser.
getManager();
384 ROS_ERROR(
"Command %s unknown", command.c_str());
bool parseArgs(int argc, char **argv)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val)
std::string getName() const
bool loadNodelet(const std::string &name, const std::string &type, const std::string &manager, const std::vector< std::string > &args, const std::string &bond_id)
Load the nodelet.
std::string getDefaultName()
ROSCPP_DECL XmlRpc::XmlRpcValue responseInt(int code, const std::string &msg, int response)
bool load(const std::string &name, const std::string &type, const M_string &remappings, const V_string &my_argv)
Load a nodelet.
std::string default_name_
std::string getType() const
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
bool call(MReq &req, MRes &res)
ROSCPP_DECL const std::string & getName()
void shutdownCallback(XmlRpc::XmlRpcValue ¶ms, XmlRpc::XmlRpcValue &result)
bool isBondEnabled() const
int main(int argc, char **argv)
ROSCPP_DECL const M_string & getRemappings()
std::map< std::string, std::string > M_string
Type const & getType() const
ROSLIB_DECL std::string command(const std::string &cmd)
#define ROS_FATAL_STREAM(args)
bool unloadNodelet(const std::string &name, const std::string &manager)
Unload the nodelet.
sig_atomic_t volatile request_shutdown
void print_usage(int argc, char **argv)
void nodeletLoaderSigIntHandler(int)
#define ROS_INFO_STREAM(args)
ROSCONSOLE_DECL void shutdown()
A class which will construct and sequentially call Nodelets according to xml This is the primary way ...
std::vector< std::string > getMyArgv() const
std::string getCommand() const
std::string getManager() const
static const XMLRPCManagerPtr & instance()
ROSCPP_DECL void shutdown()
ROSCPP_DECL void removeROSArgs(int argc, const char *const *argv, V_string &args_out)
ROSCPP_DECL bool exists(const std::string &service_name, bool print_failure_reason)
std::vector< std::string > local_args_