47 #include <visp3/core/vpConfig.h> 50 main(
int argc,
char *argv[] )
52 #if VISP_VERSION_INT > VP_VERSION_INT( 3, 2, 0 ) // ViSP >= 3.0.0 59 nll.
load( nl_name,
"visp_ros_bebop2_visual_servo_nodelet", remap, nargv );
62 if ( std::find( loaded_nodelets.begin(), loaded_nodelets.end(), nl_name ) == loaded_nodelets.end() )
65 ROS_FATAL(
"Visual servo nodelet failed to load." );
70 ROS_INFO(
"Visual servo nodelet loaded." );
73 ROS_INFO(
"This node needs ViSP > 3.2.0. Exit..." );
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 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