5 int main(
int argc,
char** argv)
11 catch (
const std::exception& e)
13 std::cerr <<
"Failed to initialize ROS: " << e.what() << std::endl;
18 std::cerr <<
"Failed to initialize ROS (unknown exception)" << std::endl;
24 ROS_INFO(
"Creating a nodelet::Loader");
29 const auto nodelet_name =
"zivid_camera/nodelet";
30 ROS_INFO(
"Loading nodelet '%s'", nodelet_name);
35 ROS_FATAL(
"Failed to load nodelet '%s'!", nodelet_name);
39 ROS_INFO(
"Successfully loaded nodelet '%s'", nodelet_name);
43 catch (
const std::exception& e)
45 std::cerr <<
"Exception occurred: " << e.what() << std::endl;
50 std::cerr <<
"Unknown exception occurred" << std::endl;
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()
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