00001 /*************************************************************************** 00002 * Copyright (C) 2012 by Markus Bader * 00003 * markus.bader@tuwien.ac.at * 00004 * * 00005 * This program is free software; you can redistribute it and/or modify * 00006 * it under the terms of the GNU General Public License as published by * 00007 * the Free Software Foundation; either version 2 of the License, or * 00008 * (at your option) any later version. * 00009 * * 00010 * This program is distributed in the hope that it will be useful, * 00011 * but WITHOUT ANY WARRANTY; without even the implied warranty of * 00012 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the * 00013 * GNU General Public License for more details. * 00014 * * 00015 * You should have received a copy of the GNU General Public License * 00016 * along with this program; if not, write to the * 00017 * Free Software Foundation, Inc., * 00018 * 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. * 00019 ***************************************************************************/ 00020 00021 00022 #include <tuw_uvc/uvc_ros.h> 00023 #include <dynamic_reconfigure/server.h> 00024 #include <tuw_uvc/CameraGeneralConfig.h> 00025 00026 class V4RLogitechNode : public V4RCamNode { 00027 public: 00028 V4RLogitechNode ( ros::NodeHandle &n ):V4RCamNode(n) { 00029 reconfigureFnc_ = boost::bind(&V4RLogitechNode::callbackParameters, this, _1, _2); 00030 reconfigureServer_.setCallback(reconfigureFnc_); 00031 } 00032 void callbackParameters ( tuw_uvc::CameraGeneralConfig &config, uint32_t level ) { 00033 show_camera_image_ = config.show_camera_image; 00034 camera_freeze_ = config.camera_freeze; 00035 queueRosParamToV4LCommit_ = true; 00036 } 00037 protected: 00038 dynamic_reconfigure::Server<tuw_uvc::CameraGeneralConfig> reconfigureServer_; 00039 dynamic_reconfigure::Server<tuw_uvc::CameraGeneralConfig>::CallbackType reconfigureFnc_; 00040 protected: 00041 }; 00042 00043 00044 int main(int argc, char **argv) 00045 { 00046 00047 ros::init(argc, argv, "tuw_uvc_general"); 00048 ros::NodeHandle n; 00049 V4RLogitechNode node(n); 00050 ros::Rate rate(100); 00051 while(ros::ok() && node.grab()) { 00052 node.publishCamera(); 00053 ros::spinOnce(); 00054 rate.sleep(); 00055 } 00056 return 0; 00057 } 00058