32 int main(
int argc,
char* argv[])
40 nll.
load(nl_name,
"bebop_driver/BebopDriverNodelet", remap, nargv);
43 if (std::find(loaded_nodelets.begin(),
44 loaded_nodelets.end(),
45 nl_name) == loaded_nodelets.end())
48 ROS_FATAL(
"bebop_driver nodelet failed to load.");
53 ROS_INFO(
"bebop_driver nodelet loaded.");
bool load(const std::string &name, const std::string &type, const M_string &remappings, const V_string &my_argv)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ROSCPP_DECL const std::string & getName()
std::vector< std::string > listLoadedNodelets()
ROSCPP_DECL void spin(Spinner &spinner)
ROSCPP_DECL const M_string & getRemappings()
ROSCPP_DECL std::string remap(const std::string &name)
int main(int argc, char *argv[])
std::vector< std::string > V_string
std::map< std::string, std::string > M_string