$search
00001 /********************************************************************* 00002 * 00003 * Software License Agreement (BSD License) 00004 * 00005 * Copyright (c) 2009, Robert Bosch LLC. 00006 * All rights reserved. 00007 * 00008 * Redistribution and use in source and binary forms, with or without 00009 * modification, are permitted provided that the following conditions 00010 * are met: 00011 * 00012 * * Redistributions of source code must retain the above copyright 00013 * notice, this list of conditions and the following disclaimer. 00014 * * Redistributions in binary form must reproduce the above 00015 * copyright notice, this list of conditions and the following 00016 * disclaimer in the documentation and/or other materials provided 00017 * with the distribution. 00018 * * Neither the name of the Robert Bosch nor the names of its 00019 * contributors may be used to endorse or promote products derived 00020 * from this software without specific prior written permission. 00021 * 00022 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00023 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00024 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00025 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00026 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00027 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00028 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00029 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00030 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00031 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00032 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00033 * POSSIBILITY OF SUCH DAMAGE. 00034 * 00035 *********************************************************************/ 00036 #include <ros/ros.h> 00037 #include <sensor_msgs/fill_image.h> 00038 #include <photo/photo.h> 00039 #include <self_test/self_test.h> 00040 00041 #include <photo/GetConfig.h> 00042 #include <photo/SetConfig.h> 00043 #include <photo/Capture.h> 00044 00045 class PhotoNode 00046 { 00047 public: 00048 photo_p photo_; 00049 photo_image_p photo_image_; 00050 boost::mutex photo_mutex_ ; 00051 00052 ros::ServiceServer set_config_srv_; 00053 ros::ServiceServer get_config_srv_; 00054 ros::ServiceServer capture_srv_; 00055 00056 PhotoNode() : photo_(NULL), photo_image_(NULL) 00057 { 00058 // initialize camera 00059 photo_image_ = photo_image_initialize(); 00060 photo_ = photo_initialize(); 00061 00062 ros::NodeHandle private_nh("~"); 00063 00064 // autodetect a digital camera 00065 if(!photo_autodetect(photo_)) { 00066 ROS_FATAL("Error: could not open connection to photo.\n"); 00067 private_nh.shutdown(); 00068 return; 00069 } 00070 00071 // ***** Start Services ***** 00072 set_config_srv_ = private_nh.advertiseService("set_config", &PhotoNode::setConfig, this); 00073 get_config_srv_ = private_nh.advertiseService("get_config", &PhotoNode::getConfig, this); 00074 capture_srv_ = private_nh.advertiseService("capture", &PhotoNode::capture, this); 00075 } 00076 00077 virtual ~PhotoNode() 00078 { 00079 // shutdown camera 00080 photo_close(photo_); 00081 photo_free(photo_); 00082 } 00083 00084 bool setConfig(photo::SetConfig::Request& req, photo::SetConfig::Response& resp) 00085 { 00086 photo_mutex_.lock(); 00087 bool ret = photo_set_config(photo_,req.param.c_str(),req.value.c_str()); 00088 photo_mutex_.unlock(); 00089 return ret; 00090 } 00091 00092 bool getConfig(photo::GetConfig::Request& req, photo::GetConfig::Response& resp) 00093 { 00094 char* value = new char[255]; 00095 photo_mutex_.lock(); 00096 bool ret = photo_get_config(photo_,req.param.c_str(),&value); 00097 if(ret) resp.value = value; 00098 photo_mutex_.unlock(); 00099 delete value; 00100 return ret; 00101 } 00102 00103 bool capture(photo::Capture::Request& req, photo::Capture::Response& resp) 00104 { 00105 // capture a camera image 00106 photo_mutex_.lock(); 00107 bool ret = photo_capture(photo_, photo_image_); 00108 if(ret) { 00109 // fill image message 00110 fillImage(resp.image, "rgb8", photo_image_->height, photo_image_->width, 3 * photo_image_->width, photo_image_->data); 00111 } 00112 photo_mutex_.unlock(); 00113 return ret; 00114 } 00115 }; 00116 00117 int main(int argc, char **argv) 00118 { 00119 ros::init(argc, argv, "photo"); 00120 PhotoNode a; 00121 ros::spin(); 00122 00123 return 0; 00124 }