Go to the documentation of this file.
   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..." );
 
  
std::vector< std::string > V_string
std::map< std::string, std::string > M_string
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
bool load(const std::string &name, const std::string &type, const M_string &remappings, const V_string &my_argv)
const ROSCPP_DECL M_string & getRemappings()
ROSCPP_DECL std::string remap(const std::string &name)
const ROSCPP_DECL std::string & getName()
int main(int argc, char *argv[])
std::vector< std::string > listLoadedNodelets()
visp_ros
Author(s): Francois Pasteau, Fabien Spindler, Gatien Gaumerais, Alexander Oliva
autogenerated on Wed Mar 2 2022 01:13:33