general_node.cpp
Go to the documentation of this file.
1 /***************************************************************************
2  * Copyright (C) 2012 by Markus Bader *
3  * markus.bader@tuwien.ac.at *
4  * *
5  * This program is free software; you can redistribute it and/or modify *
6  * it under the terms of the GNU General Public License as published by *
7  * the Free Software Foundation; either version 2 of the License, or *
8  * (at your option) any later version. *
9  * *
10  * This program is distributed in the hope that it will be useful, *
11  * but WITHOUT ANY WARRANTY; without even the implied warranty of *
12  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the *
13  * GNU General Public License for more details. *
14  * *
15  * You should have received a copy of the GNU General Public License *
16  * along with this program; if not, write to the *
17  * Free Software Foundation, Inc., *
18  * 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA. *
19  ***************************************************************************/
20 
21 
22 #include <tuw_uvc/uvc_ros.h>
23 #include <dynamic_reconfigure/server.h>
24 #include <tuw_uvc/CameraGeneralConfig.h>
25 
26 class V4RLogitechNode : public V4RCamNode {
27 public:
29  reconfigureFnc_ = boost::bind(&V4RLogitechNode::callbackParameters, this, _1, _2);
31  }
32  void callbackParameters ( tuw_uvc::CameraGeneralConfig &config, uint32_t level ) {
33  show_camera_image_ = config.show_camera_image;
34  camera_freeze_ = config.camera_freeze;
36  }
37 protected:
38  dynamic_reconfigure::Server<tuw_uvc::CameraGeneralConfig> reconfigureServer_;
39  dynamic_reconfigure::Server<tuw_uvc::CameraGeneralConfig>::CallbackType reconfigureFnc_;
40 protected:
41 };
42 
43 
44 int main(int argc, char **argv)
45 {
46 
47  ros::init(argc, argv, "tuw_uvc_general");
49  V4RLogitechNode node(n);
50  ros::Rate rate(100);
51  while(ros::ok() && node.grab()) {
52  node.publishCamera();
53  ros::spinOnce();
54  rate.sleep();
55  }
56  return 0;
57 }
58 
bool queueRosParamToV4LCommit_
Definition: uvc_ros.h:61
int main(int argc, char **argv)
bool camera_freeze_
Definition: uvc_ros.h:60
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
dynamic_reconfigure::Server< tuw_uvc::CameraGeneralConfig > reconfigureServer_
bool grab()
destructor
Definition: uvc.cpp:105
ROS camera abstraction.
Definition: uvc_ros.h:34
dynamic_reconfigure::Server< tuw_uvc::CameraGeneralConfig >::CallbackType reconfigureFnc_
ROSCPP_DECL bool ok()
bool sleep()
V4RLogitechNode(ros::NodeHandle &n)
bool show_camera_image_
Definition: uvc_ros.h:59
void callbackParameters(tuw_uvc::CameraGeneralConfig &config, uint32_t level)
void publishCamera()
Definition: uvc_ros.cpp:183
ROSCPP_DECL void spinOnce()


tuw_uvc
Author(s): Markus Bader
autogenerated on Mon Jun 10 2019 15:39:24