00001 #include <ros/ros.h> 00002 #include <nodelet/nodelet.h> 00003 #include <pluginlib/class_list_macros.h> 00004 #include <sstream> 00005 #include "offscreenRendererNodelet.h" 00006 00007 PLUGINLIB_DECLARE_CLASS(offscreen_renderer,offscreenrenderer_nodelet,offscreen_renderer::OffscreenRendererNodelet,nodelet::Nodelet) 00008 00009 namespace offscreen_renderer 00010 { 00011 void OffscreenRendererNodelet::onInit() 00012 { 00013 try 00014 { 00015 nodelet::V_string argv=getMyArgv(); 00016 if(argv.size()<1) 00017 { 00018 ROS_ERROR("Render nodelet requires arguments: camera_field"); 00019 exit(-1); 00020 } 00021 00022 std::stringstream ss_camera_topic; 00023 ss_camera_topic << argv[0] << "camera_info"; 00024 00025 rve_render_server::init(true, "render_server"); 00026 rve_render_client::init(); 00027 00028 rve_render_client::ClientContextPtr context = 00029 rve_render_client::createContext("render_server", ros::NodeHandle("render_server")); 00030 offscreen_renderer_ = new OffscreenRenderer(context,ss_camera_topic.str(),getNodeHandle()); 00031 } 00032 catch (std::exception& e) 00033 { 00034 ROS_ERROR("Caught exception: %s", e.what()); 00035 } 00036 } 00037 } // namespace offscreen_renderer