45 #include <photo/GetConfig.h> 46 #include <photo/SetConfig.h> 47 #include <photo/Capture.h> 75 GPContext* private_context;
83 if( camera_list_.
autodetect( private_context ) == false )
85 ROS_FATAL(
"photo_node: Autodetection of cameras failed." );
86 gp_context_unref( private_context );
94 ROS_FATAL(
"photo_node: Could not open camera %d.", 0 );
95 gp_context_unref( private_context );
112 bool setConfig( photo::SetConfig::Request& req, photo::SetConfig::Response& resp )
116 photo_mutex_.unlock();
120 bool getConfig( photo::GetConfig::Request& req, photo::GetConfig::Response& resp )
122 char* value =
new char[255];
129 photo_mutex_.unlock();
134 bool capture( photo::Capture::Request& req, photo::Capture::Response& resp )
144 photo_mutex_.unlock();
149 int main(
int argc,
char **argv)
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 ¶m, const std::string &value)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
boost::mutex photo_mutex_
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
bool setConfig(photo::SetConfig::Request &req, photo::SetConfig::Response &resp)
bool photo_camera_open(photo_camera_list *list, int n)
ros::ServiceServer set_config_srv_
bool capture(photo::Capture::Request &req, photo::Capture::Response &resp)
char * getDataAddress(void)
size_t getBytesPerPixel(void)
ros::ServiceServer get_config_srv_
bool photo_camera_close(void)
int main(int argc, char **argv)
photo_camera_list camera_list_
ros::ServiceServer capture_srv_
bool getConfig(photo::GetConfig::Request &req, photo::GetConfig::Response &resp)