photo_node.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  *
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2009, Robert Bosch LLC.
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * * Neither the name of the Robert Bosch nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *
35  *********************************************************************/
36 
37 // ROS Headers
38 #include <ros/ros.h>
39 #include <self_test/self_test.h>
40 
41 // ROS Messages
42 #include <sensor_msgs/fill_image.h>
43 
44 // ROS Services
45 #include <photo/GetConfig.h>
46 #include <photo/SetConfig.h>
47 #include <photo/Capture.h>
48 
49 // photo library headers
51 #include "photo/photo_camera.hpp"
52 #include "photo/photo_image.hpp"
53 
54 
55 class PhotoNode
56 {
57 public:
61 
62  boost::mutex photo_mutex_ ;
63 
67 
69  camera_list_(),
70  camera_(),
71  image_()
72  {
73 
74  ros::NodeHandle private_nh("~");
75  GPContext* private_context;
76 
77  // initialize camera
78 
79  // create context
80  private_context = camera_.photo_camera_create_context();
81 
82  // autodetect all cameras connected
83  if( camera_list_.autodetect( private_context ) == false )
84  {
85  ROS_FATAL( "photo_node: Autodetection of cameras failed." );
86  gp_context_unref( private_context );
87  private_nh.shutdown();
88  return;
89  }
90 
91  // open camera from camera list
92  if( camera_.photo_camera_open( &camera_list_, 0 ) == false )
93  {
94  ROS_FATAL( "photo_node: Could not open camera %d.", 0 );
95  gp_context_unref( private_context );
96  private_nh.shutdown();
97  return;
98  }
99 
100  // ***** Start Services *****
101  set_config_srv_ = private_nh.advertiseService("set_config", &PhotoNode::setConfig, this);
102  get_config_srv_ = private_nh.advertiseService("get_config", &PhotoNode::getConfig, this);
103  capture_srv_ = private_nh.advertiseService("capture", &PhotoNode::capture, this);
104  }
105 
107  {
108  // shutdown camera
109  camera_.photo_camera_close();
110  }
111 
112  bool setConfig( photo::SetConfig::Request& req, photo::SetConfig::Response& resp )
113  {
114  photo_mutex_.lock();
115  bool error_code = camera_.photo_camera_set_config( req.param, req.value );
116  photo_mutex_.unlock();
117  return error_code;
118  }
119 
120  bool getConfig( photo::GetConfig::Request& req, photo::GetConfig::Response& resp )
121  {
122  char* value = new char[255];
123  photo_mutex_.lock();
124  bool error_code = camera_.photo_camera_get_config( req.param, &value );
125  if( error_code )
126  {
127  resp.value = value;
128  }
129  photo_mutex_.unlock();
130  delete[] value;
131  return error_code;
132  }
133 
134  bool capture( photo::Capture::Request& req, photo::Capture::Response& resp )
135  {
136  // capture a camera image
137  photo_mutex_.lock();
138  bool error_code = camera_.photo_camera_capture( &image_ );
139  if( error_code )
140  {
141  // fill image message
142  fillImage( resp.image, "rgb8", image_.getHeight(), image_.getWidth(), image_.getBytesPerPixel() * image_.getWidth(), image_.getDataAddress() );
143  }
144  photo_mutex_.unlock();
145  return error_code;
146  }
147 };
148 
149 int main(int argc, char **argv)
150 {
151  ros::init(argc, argv, "photo");
152  PhotoNode a;
153  ros::spin();
154 
155  return 0;
156 }
#define ROS_FATAL(...)
bool photo_camera_get_config(const std::string &, char **value)
bool photo_camera_capture(photo_image *image)
bool autodetect(GPContext *context)
GPContext * photo_camera_create_context(void)
bool photo_camera_set_config(const std::string &param, const std::string &value)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
boost::mutex photo_mutex_
Definition: photo_node.cpp:62
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
bool setConfig(photo::SetConfig::Request &req, photo::SetConfig::Response &resp)
Definition: photo_node.cpp:112
bool photo_camera_open(photo_camera_list *list, int n)
ros::ServiceServer set_config_srv_
Definition: photo_node.cpp:64
bool capture(photo::Capture::Request &req, photo::Capture::Response &resp)
Definition: photo_node.cpp:134
int getHeight(void)
Definition: photo_image.cpp:63
int getWidth(void)
Definition: photo_image.cpp:58
char * getDataAddress(void)
Definition: photo_image.cpp:78
ROSCPP_DECL void spin()
size_t getBytesPerPixel(void)
Definition: photo_image.cpp:68
ros::ServiceServer get_config_srv_
Definition: photo_node.cpp:65
bool photo_camera_close(void)
photo_camera camera_
Definition: photo_node.cpp:59
int main(int argc, char **argv)
Definition: photo_node.cpp:149
photo_camera_list camera_list_
Definition: photo_node.cpp:58
ros::ServiceServer capture_srv_
Definition: photo_node.cpp:66
bool getConfig(photo::GetConfig::Request &req, photo::GetConfig::Response &resp)
Definition: photo_node.cpp:120
photo_image image_
Definition: photo_node.cpp:60


photo
Author(s): Benjamin Pitzer
autogenerated on Mon Feb 28 2022 23:12:30