00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039
00040
00041
00042
00043
00044
00045
00046
00047 #ifndef __camera1394__CAMERA1394CONFIG_H__
00048 #define __camera1394__CAMERA1394CONFIG_H__
00049
00050 #include <dynamic_reconfigure/config_tools.h>
00051 #include <limits>
00052 #include <ros/node_handle.h>
00053 #include <dynamic_reconfigure/ConfigDescription.h>
00054 #include <dynamic_reconfigure/ParamDescription.h>
00055 #include <dynamic_reconfigure/config_init_mutex.h>
00056
00057 namespace camera1394
00058 {
00059 class Camera1394ConfigStatics;
00060
00061 class Camera1394Config
00062 {
00063 public:
00064 class AbstractParamDescription : public dynamic_reconfigure::ParamDescription
00065 {
00066 public:
00067 AbstractParamDescription(std::string n, std::string t, uint32_t l,
00068 std::string d, std::string e)
00069 {
00070 name = n;
00071 type = t;
00072 level = l;
00073 description = d;
00074 edit_method = e;
00075 }
00076
00077 virtual void clamp(Camera1394Config &config, const Camera1394Config &max, const Camera1394Config &min) const = 0;
00078 virtual void calcLevel(uint32_t &level, const Camera1394Config &config1, const Camera1394Config &config2) const = 0;
00079 virtual void fromServer(const ros::NodeHandle &nh, Camera1394Config &config) const = 0;
00080 virtual void toServer(const ros::NodeHandle &nh, const Camera1394Config &config) const = 0;
00081 virtual bool fromMessage(const dynamic_reconfigure::Config &msg, Camera1394Config &config) const = 0;
00082 virtual void toMessage(dynamic_reconfigure::Config &msg, const Camera1394Config &config) const = 0;
00083 };
00084
00085 typedef boost::shared_ptr<AbstractParamDescription> AbstractParamDescriptionPtr;
00086 typedef boost::shared_ptr<const AbstractParamDescription> AbstractParamDescriptionConstPtr;
00087
00088 template <class T>
00089 class ParamDescription : public AbstractParamDescription
00090 {
00091 public:
00092 ParamDescription(std::string name, std::string type, uint32_t level,
00093 std::string description, std::string edit_method, T Camera1394Config::* f) :
00094 AbstractParamDescription(name, type, level, description, edit_method),
00095 field(f)
00096 {}
00097
00098 T (Camera1394Config::* field);
00099
00100 virtual void clamp(Camera1394Config &config, const Camera1394Config &max, const Camera1394Config &min) const
00101 {
00102 if (config.*field > max.*field)
00103 config.*field = max.*field;
00104
00105 if (config.*field < min.*field)
00106 config.*field = min.*field;
00107 }
00108
00109 virtual void calcLevel(uint32_t &comb_level, const Camera1394Config &config1, const Camera1394Config &config2) const
00110 {
00111 if (config1.*field != config2.*field)
00112 comb_level |= level;
00113 }
00114
00115 virtual void fromServer(const ros::NodeHandle &nh, Camera1394Config &config) const
00116 {
00117 nh.getParam(name, config.*field);
00118 }
00119
00120 virtual void toServer(const ros::NodeHandle &nh, const Camera1394Config &config) const
00121 {
00122 nh.setParam(name, config.*field);
00123 }
00124
00125 virtual bool fromMessage(const dynamic_reconfigure::Config &msg, Camera1394Config &config) const
00126 {
00127 return dynamic_reconfigure::ConfigTools::getParameter(msg, name, config.*field);
00128 }
00129
00130 virtual void toMessage(dynamic_reconfigure::Config &msg, const Camera1394Config &config) const
00131 {
00132 dynamic_reconfigure::ConfigTools::appendParameter(msg, name, config.*field);
00133 }
00134 };
00135
00136
00137 std::string guid;
00138
00139 bool reset_on_open;
00140
00141 std::string video_mode;
00142
00143 std::string frame_id;
00144
00145 double frame_rate;
00146
00147 int iso_speed;
00148
00149 std::string camera_info_url;
00150
00151 int binning_x;
00152
00153 int binning_y;
00154
00155 int roi_width;
00156
00157 int roi_height;
00158
00159 int x_offset;
00160
00161 int y_offset;
00162
00163 int format7_packet_size;
00164
00165 std::string format7_color_coding;
00166
00167 std::string bayer_pattern;
00168
00169 std::string bayer_method;
00170
00171 int auto_brightness;
00172
00173 double brightness;
00174
00175 int auto_exposure;
00176
00177 double exposure;
00178
00179 int auto_focus;
00180
00181 double focus;
00182
00183 int auto_gain;
00184
00185 double gain;
00186
00187 int auto_gamma;
00188
00189 double gamma;
00190
00191 int auto_hue;
00192
00193 double hue;
00194
00195 int auto_iris;
00196
00197 double iris;
00198
00199 int auto_saturation;
00200
00201 double saturation;
00202
00203 int auto_sharpness;
00204
00205 double sharpness;
00206
00207 int auto_shutter;
00208
00209 double shutter;
00210
00211 int auto_white_balance;
00212
00213 double white_balance_BU;
00214
00215 double white_balance_RV;
00216
00217 int auto_zoom;
00218
00219 double zoom;
00220
00221 bool use_ros_time;
00222
00223
00224 bool __fromMessage__(dynamic_reconfigure::Config &msg)
00225 {
00226 const std::vector<AbstractParamDescriptionConstPtr> &__param_descriptions__ = __getParamDescriptions__();
00227 int count = 0;
00228 for (std::vector<AbstractParamDescriptionConstPtr>::const_iterator i = __param_descriptions__.begin(); i != __param_descriptions__.end(); i++)
00229 if ((*i)->fromMessage(msg, *this))
00230 count++;
00231 if (count != dynamic_reconfigure::ConfigTools::size(msg))
00232 {
00233 ROS_ERROR("Camera1394Config::__fromMessage__ called with an unexpected parameter.");
00234 ROS_ERROR("Booleans:");
00235 for (unsigned int i = 0; i < msg.bools.size(); i++)
00236 ROS_ERROR(" %s", msg.bools[i].name.c_str());
00237 ROS_ERROR("Integers:");
00238 for (unsigned int i = 0; i < msg.ints.size(); i++)
00239 ROS_ERROR(" %s", msg.ints[i].name.c_str());
00240 ROS_ERROR("Doubles:");
00241 for (unsigned int i = 0; i < msg.doubles.size(); i++)
00242 ROS_ERROR(" %s", msg.doubles[i].name.c_str());
00243 ROS_ERROR("Strings:");
00244 for (unsigned int i = 0; i < msg.strs.size(); i++)
00245 ROS_ERROR(" %s", msg.strs[i].name.c_str());
00246
00247
00248 return false;
00249 }
00250 return true;
00251 }
00252
00253
00254
00255 void __toMessage__(dynamic_reconfigure::Config &msg, const std::vector<AbstractParamDescriptionConstPtr> &__param_descriptions__) const
00256 {
00257 dynamic_reconfigure::ConfigTools::clear(msg);
00258 for (std::vector<AbstractParamDescriptionConstPtr>::const_iterator i = __param_descriptions__.begin(); i != __param_descriptions__.end(); i++)
00259 (*i)->toMessage(msg, *this);
00260 }
00261
00262 void __toMessage__(dynamic_reconfigure::Config &msg) const
00263 {
00264 const std::vector<AbstractParamDescriptionConstPtr> &__param_descriptions__ = __getParamDescriptions__();
00265 __toMessage__(msg, __param_descriptions__);
00266 }
00267
00268 void __toServer__(const ros::NodeHandle &nh) const
00269 {
00270 const std::vector<AbstractParamDescriptionConstPtr> &__param_descriptions__ = __getParamDescriptions__();
00271 for (std::vector<AbstractParamDescriptionConstPtr>::const_iterator i = __param_descriptions__.begin(); i != __param_descriptions__.end(); i++)
00272 (*i)->toServer(nh, *this);
00273 }
00274
00275 void __fromServer__(const ros::NodeHandle &nh)
00276 {
00277 const std::vector<AbstractParamDescriptionConstPtr> &__param_descriptions__ = __getParamDescriptions__();
00278 for (std::vector<AbstractParamDescriptionConstPtr>::const_iterator i = __param_descriptions__.begin(); i != __param_descriptions__.end(); i++)
00279 (*i)->fromServer(nh, *this);
00280 }
00281
00282 void __clamp__()
00283 {
00284 const std::vector<AbstractParamDescriptionConstPtr> &__param_descriptions__ = __getParamDescriptions__();
00285 const Camera1394Config &__max__ = __getMax__();
00286 const Camera1394Config &__min__ = __getMin__();
00287 for (std::vector<AbstractParamDescriptionConstPtr>::const_iterator i = __param_descriptions__.begin(); i != __param_descriptions__.end(); i++)
00288 (*i)->clamp(*this, __max__, __min__);
00289 }
00290
00291 uint32_t __level__(const Camera1394Config &config) const
00292 {
00293 const std::vector<AbstractParamDescriptionConstPtr> &__param_descriptions__ = __getParamDescriptions__();
00294 uint32_t level = 0;
00295 for (std::vector<AbstractParamDescriptionConstPtr>::const_iterator i = __param_descriptions__.begin(); i != __param_descriptions__.end(); i++)
00296 (*i)->calcLevel(level, config, *this);
00297 return level;
00298 }
00299
00300 static const dynamic_reconfigure::ConfigDescription &__getDescriptionMessage__();
00301 static const Camera1394Config &__getDefault__();
00302 static const Camera1394Config &__getMax__();
00303 static const Camera1394Config &__getMin__();
00304 static const std::vector<AbstractParamDescriptionConstPtr> &__getParamDescriptions__();
00305
00306 private:
00307 static const Camera1394ConfigStatics *__get_statics__();
00308 };
00309
00310 template <>
00311 inline void Camera1394Config::ParamDescription<std::string>::clamp(Camera1394Config &config, const Camera1394Config &max, const Camera1394Config &min) const
00312 {
00313 return;
00314 }
00315
00316 class Camera1394ConfigStatics
00317 {
00318 friend class Camera1394Config;
00319
00320 Camera1394ConfigStatics()
00321 {
00322
00323 __min__.guid = "";
00324
00325 __max__.guid = "";
00326
00327 __default__.guid = "";
00328
00329 __param_descriptions__.push_back(Camera1394Config::AbstractParamDescriptionConstPtr(new Camera1394Config::ParamDescription<std::string>("guid", "str", 3, "Global Unique ID of camera, 16 hex digits (use first camera if null).", "", &Camera1394Config::guid)));
00330
00331 __min__.reset_on_open = 0;
00332
00333 __max__.reset_on_open = 1;
00334
00335 __default__.reset_on_open = 0;
00336
00337 __param_descriptions__.push_back(Camera1394Config::AbstractParamDescriptionConstPtr(new Camera1394Config::ParamDescription<bool>("reset_on_open", "bool", 3, "Reset camera when opening the device.", "", &Camera1394Config::reset_on_open)));
00338
00339 __min__.video_mode = "";
00340
00341 __max__.video_mode = "";
00342
00343 __default__.video_mode = "640x480_mono8";
00344
00345 __param_descriptions__.push_back(Camera1394Config::AbstractParamDescriptionConstPtr(new Camera1394Config::ParamDescription<std::string>("video_mode", "str", 3, "IIDC video mode.", "{'enum_description': 'Video mode for camera.', 'enum': [{'srcline': 54, 'description': '', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const char * const', 'value': '160x120_yuv444', 'ctype': 'std::string', 'type': 'str', 'name': 'Format0_Mode0'}, {'srcline': 55, 'description': '', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const char * const', 'value': '320x240_yuv422', 'ctype': 'std::string', 'type': 'str', 'name': 'Format0_Mode1'}, {'srcline': 56, 'description': '', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const char * const', 'value': '640x480_yuv411', 'ctype': 'std::string', 'type': 'str', 'name': 'Format0_Mode2'}, {'srcline': 57, 'description': '', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const char * const', 'value': '640x480_yuv422', 'ctype': 'std::string', 'type': 'str', 'name': 'Format0_Mode3'}, {'srcline': 58, 'description': '', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const char * const', 'value': '640x480_rgb8', 'ctype': 'std::string', 'type': 'str', 'name': 'Format0_Mode4'}, {'srcline': 59, 'description': '', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const char * const', 'value': '640x480_mono8', 'ctype': 'std::string', 'type': 'str', 'name': 'Format0_Mode5'}, {'srcline': 60, 'description': '', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const char * const', 'value': '640x480_mono16', 'ctype': 'std::string', 'type': 'str', 'name': 'Format0_Mode6'}, {'srcline': 61, 'description': '', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const char * const', 'value': '800x600_yuv422', 'ctype': 'std::string', 'type': 'str', 'name': 'Format1_Mode0'}, {'srcline': 62, 'description': '', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const char * const', 'value': '800x600_rgb8', 'ctype': 'std::string', 'type': 'str', 'name': 'Format1_Mode1'}, {'srcline': 63, 'description': '', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const char * const', 'value': '800x600_mono8', 'ctype': 'std::string', 'type': 'str', 'name': 'Format1_Mode2'}, {'srcline': 64, 'description': '', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const char * const', 'value': '800x600_mono16', 'ctype': 'std::string', 'type': 'str', 'name': 'Format1_Mode6'}, {'srcline': 65, 'description': '', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const char * const', 'value': '1024x768_yuv422', 'ctype': 'std::string', 'type': 'str', 'name': 'Format1_Mode3'}, {'srcline': 66, 'description': '', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const char * const', 'value': '1024x768_rgb8', 'ctype': 'std::string', 'type': 'str', 'name': 'Format1_Mode4'}, {'srcline': 67, 'description': '', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const char * const', 'value': '1024x768_mono8', 'ctype': 'std::string', 'type': 'str', 'name': 'Format1_Mode5'}, {'srcline': 68, 'description': '', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const char * const', 'value': '1024x768_mono16', 'ctype': 'std::string', 'type': 'str', 'name': 'Format1_Mode7'}, {'srcline': 69, 'description': '', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const char * const', 'value': '1280x960_yuv422', 'ctype': 'std::string', 'type': 'str', 'name': 'Format2_Mode0'}, {'srcline': 70, 'description': '', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const char * const', 'value': '1280x960_rgb8', 'ctype': 'std::string', 'type': 'str', 'name': 'Format2_Mode1'}, {'srcline': 71, 'description': '', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const char * const', 'value': '1280x960_mono8', 'ctype': 'std::string', 'type': 'str', 'name': 'Format2_Mode2'}, {'srcline': 72, 'description': '', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const char * const', 'value': '1280x960_mono16', 'ctype': 'std::string', 'type': 'str', 'name': 'Format2_Mode6'}, {'srcline': 73, 'description': '', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const char * const', 'value': '1600x1200_yuv422', 'ctype': 'std::string', 'type': 'str', 'name': 'Format2_Mode3'}, {'srcline': 74, 'description': '', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const char * const', 'value': '1600x1200_rgb8', 'ctype': 'std::string', 'type': 'str', 'name': 'Format2_Mode4'}, {'srcline': 75, 'description': '', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const char * const', 'value': '1600x1200_mono8', 'ctype': 'std::string', 'type': 'str', 'name': 'Format2_Mode5'}, {'srcline': 76, 'description': '', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const char * const', 'value': '1600x1200_mono16', 'ctype': 'std::string', 'type': 'str', 'name': 'Format2_Mode7'}, {'srcline': 77, 'description': '', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const char * const', 'value': 'format7_mode0', 'ctype': 'std::string', 'type': 'str', 'name': 'Format7_Mode0'}, {'srcline': 78, 'description': '', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const char * const', 'value': 'format7_mode1', 'ctype': 'std::string', 'type': 'str', 'name': 'Format7_Mode1'}, {'srcline': 79, 'description': '', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const char * const', 'value': 'format7_mode2', 'ctype': 'std::string', 'type': 'str', 'name': 'Format7_Mode2'}, {'srcline': 80, 'description': '', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const char * const', 'value': 'format7_mode3', 'ctype': 'std::string', 'type': 'str', 'name': 'Format7_Mode3'}, {'srcline': 81, 'description': '', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const char * const', 'value': 'format7_mode4', 'ctype': 'std::string', 'type': 'str', 'name': 'Format7_Mode4'}, {'srcline': 82, 'description': '', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const char * const', 'value': 'format7_mode5', 'ctype': 'std::string', 'type': 'str', 'name': 'Format7_Mode5'}, {'srcline': 83, 'description': '', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const char * const', 'value': 'format7_mode6', 'ctype': 'std::string', 'type': 'str', 'name': 'Format7_Mode6'}, {'srcline': 84, 'description': '', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const char * const', 'value': 'format7_mode7', 'ctype': 'std::string', 'type': 'str', 'name': 'Format7_Mode7'}]}", &Camera1394Config::video_mode)));
00346
00347 __min__.frame_id = "";
00348
00349 __max__.frame_id = "";
00350
00351 __default__.frame_id = "camera";
00352
00353 __param_descriptions__.push_back(Camera1394Config::AbstractParamDescriptionConstPtr(new Camera1394Config::ParamDescription<std::string>("frame_id", "str", 3, "ROS tf frame of reference, resolved with tf_prefix unless absolute.", "", &Camera1394Config::frame_id)));
00354
00355 __min__.frame_rate = 1.875;
00356
00357 __max__.frame_rate = 240.0;
00358
00359 __default__.frame_rate = 15.0;
00360
00361 __param_descriptions__.push_back(Camera1394Config::AbstractParamDescriptionConstPtr(new Camera1394Config::ParamDescription<double>("frame_rate", "double", 3, "Camera speed (frames per second).", "", &Camera1394Config::frame_rate)));
00362
00363 __min__.iso_speed = 100;
00364
00365 __max__.iso_speed = 3200;
00366
00367 __default__.iso_speed = 400;
00368
00369 __param_descriptions__.push_back(Camera1394Config::AbstractParamDescriptionConstPtr(new Camera1394Config::ParamDescription<int>("iso_speed", "int", 3, "Total IEEE 1394 bus bandwidth (Megabits/second).", "", &Camera1394Config::iso_speed)));
00370
00371 __min__.camera_info_url = "";
00372
00373 __max__.camera_info_url = "";
00374
00375 __default__.camera_info_url = "";
00376
00377 __param_descriptions__.push_back(Camera1394Config::AbstractParamDescriptionConstPtr(new Camera1394Config::ParamDescription<std::string>("camera_info_url", "str", 0, "Camera [[camera_info_manager#URL_Names|calibration URL]] for this video_mode (uncalibrated if null).", "", &Camera1394Config::camera_info_url)));
00378
00379 __min__.binning_x = 0;
00380
00381 __max__.binning_x = 4;
00382
00383 __default__.binning_x = 0;
00384
00385 __param_descriptions__.push_back(Camera1394Config::AbstractParamDescriptionConstPtr(new Camera1394Config::ParamDescription<int>("binning_x", "int", 3, "Number of pixels combined for Format7 horizontal binning, use device hints if zero.", "", &Camera1394Config::binning_x)));
00386
00387 __min__.binning_y = 0;
00388
00389 __max__.binning_y = 4;
00390
00391 __default__.binning_y = 0;
00392
00393 __param_descriptions__.push_back(Camera1394Config::AbstractParamDescriptionConstPtr(new Camera1394Config::ParamDescription<int>("binning_y", "int", 3, "Number of pixels combined for Format7 vertical binning, use device hints if zero.", "", &Camera1394Config::binning_y)));
00394
00395 __min__.roi_width = 0;
00396
00397 __max__.roi_width = 65535;
00398
00399 __default__.roi_width = 0;
00400
00401 __param_descriptions__.push_back(Camera1394Config::AbstractParamDescriptionConstPtr(new Camera1394Config::ParamDescription<int>("roi_width", "int", 3, "Width of Format7 Region of Interest in unbinned pixels, full width if zero.", "", &Camera1394Config::roi_width)));
00402
00403 __min__.roi_height = 0;
00404
00405 __max__.roi_height = 65535;
00406
00407 __default__.roi_height = 0;
00408
00409 __param_descriptions__.push_back(Camera1394Config::AbstractParamDescriptionConstPtr(new Camera1394Config::ParamDescription<int>("roi_height", "int", 3, "Height of Format7 Region of Interest in unbinned pixels, full height if zero.", "", &Camera1394Config::roi_height)));
00410
00411 __min__.x_offset = 0;
00412
00413 __max__.x_offset = 65535;
00414
00415 __default__.x_offset = 0;
00416
00417 __param_descriptions__.push_back(Camera1394Config::AbstractParamDescriptionConstPtr(new Camera1394Config::ParamDescription<int>("x_offset", "int", 3, "Horizontal offset for left side of Format7 ROI in unbinned pixels.", "", &Camera1394Config::x_offset)));
00418
00419 __min__.y_offset = 0;
00420
00421 __max__.y_offset = 65535;
00422
00423 __default__.y_offset = 0;
00424
00425 __param_descriptions__.push_back(Camera1394Config::AbstractParamDescriptionConstPtr(new Camera1394Config::ParamDescription<int>("y_offset", "int", 3, "Vertical offset for top of Format7 ROI in unbinned pixels.", "", &Camera1394Config::y_offset)));
00426
00427 __min__.format7_packet_size = 0;
00428
00429 __max__.format7_packet_size = 39320;
00430
00431 __default__.format7_packet_size = 0;
00432
00433 __param_descriptions__.push_back(Camera1394Config::AbstractParamDescriptionConstPtr(new Camera1394Config::ParamDescription<int>("format7_packet_size", "int", 3, "Format7 packet size (bytes), device-recommended size if zero.", "", &Camera1394Config::format7_packet_size)));
00434
00435 __min__.format7_color_coding = "";
00436
00437 __max__.format7_color_coding = "";
00438
00439 __default__.format7_color_coding = "mono8";
00440
00441 __param_descriptions__.push_back(Camera1394Config::AbstractParamDescriptionConstPtr(new Camera1394Config::ParamDescription<std::string>("format7_color_coding", "str", 3, "Color coding (only for Format7 modes)", "{'enum_description': 'Format7 color coding methods', 'enum': [{'srcline': 133, 'description': '', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const char * const', 'value': 'mono8', 'ctype': 'std::string', 'type': 'str', 'name': 'mono8'}, {'srcline': 134, 'description': '', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const char * const', 'value': 'mono16', 'ctype': 'std::string', 'type': 'str', 'name': 'mono16'}, {'srcline': 135, 'description': '', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const char * const', 'value': 'mono16s', 'ctype': 'std::string', 'type': 'str', 'name': 'mono16s'}, {'srcline': 136, 'description': '', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const char * const', 'value': 'raw8', 'ctype': 'std::string', 'type': 'str', 'name': 'raw8'}, {'srcline': 137, 'description': '', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const char * const', 'value': 'raw16', 'ctype': 'std::string', 'type': 'str', 'name': 'raw16'}, {'srcline': 138, 'description': '', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const char * const', 'value': 'rgb8', 'ctype': 'std::string', 'type': 'str', 'name': 'rgb8'}, {'srcline': 139, 'description': '', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const char * const', 'value': 'rgb16', 'ctype': 'std::string', 'type': 'str', 'name': 'rgb16'}, {'srcline': 140, 'description': '', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const char * const', 'value': 'rgb16s', 'ctype': 'std::string', 'type': 'str', 'name': 'rgb16s'}, {'srcline': 141, 'description': '', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const char * const', 'value': 'yuv411', 'ctype': 'std::string', 'type': 'str', 'name': 'yuv411'}, {'srcline': 142, 'description': '', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const char * const', 'value': 'yuv422', 'ctype': 'std::string', 'type': 'str', 'name': 'yuv422'}, {'srcline': 143, 'description': '', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const char * const', 'value': 'yuv444', 'ctype': 'std::string', 'type': 'str', 'name': 'yuv444'}]}", &Camera1394Config::format7_color_coding)));
00442
00443 __min__.bayer_pattern = "";
00444
00445 __max__.bayer_pattern = "";
00446
00447 __default__.bayer_pattern = "";
00448
00449 __param_descriptions__.push_back(Camera1394Config::AbstractParamDescriptionConstPtr(new Camera1394Config::ParamDescription<std::string>("bayer_pattern", "str", 3, "Bayer color encoding pattern (default: none).", "{'enum_description': 'Bayer color encoding patterns', 'enum': [{'srcline': 151, 'description': 'No Bayer encoding', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const char * const', 'value': '', 'ctype': 'std::string', 'type': 'str', 'name': 'none'}, {'srcline': 152, 'description': '', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const char * const', 'value': 'rggb', 'ctype': 'std::string', 'type': 'str', 'name': 'rggb'}, {'srcline': 153, 'description': '', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const char * const', 'value': 'gbrg', 'ctype': 'std::string', 'type': 'str', 'name': 'gbrg'}, {'srcline': 154, 'description': '', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const char * const', 'value': 'grbg', 'ctype': 'std::string', 'type': 'str', 'name': 'grbg'}, {'srcline': 155, 'description': '', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const char * const', 'value': 'bggr', 'ctype': 'std::string', 'type': 'str', 'name': 'bggr'}]}", &Camera1394Config::bayer_pattern)));
00450
00451 __min__.bayer_method = "";
00452
00453 __max__.bayer_method = "";
00454
00455 __default__.bayer_method = "";
00456
00457 __param_descriptions__.push_back(Camera1394Config::AbstractParamDescriptionConstPtr(new Camera1394Config::ParamDescription<std::string>("bayer_method", "str", 3, "Bayer decoding method (default: ROS image_proc).", "{'enum_description': 'Bayer method', 'enum': [{'srcline': 163, 'description': 'Decode via ROS image_proc', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const char * const', 'value': '', 'ctype': 'std::string', 'type': 'str', 'name': 'image_proc'}, {'srcline': 164, 'description': '', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const char * const', 'value': 'DownSample', 'ctype': 'std::string', 'type': 'str', 'name': 'DownSample'}, {'srcline': 165, 'description': '', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const char * const', 'value': 'Simple', 'ctype': 'std::string', 'type': 'str', 'name': 'Simple'}, {'srcline': 166, 'description': '', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const char * const', 'value': 'Bilinear', 'ctype': 'std::string', 'type': 'str', 'name': 'Bilinear'}, {'srcline': 167, 'description': '', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const char * const', 'value': 'HQ', 'ctype': 'std::string', 'type': 'str', 'name': 'HQ'}, {'srcline': 168, 'description': '', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const char * const', 'value': 'VNG', 'ctype': 'std::string', 'type': 'str', 'name': 'VNG'}, {'srcline': 169, 'description': '', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const char * const', 'value': 'AHD', 'ctype': 'std::string', 'type': 'str', 'name': 'AHD'}]}", &Camera1394Config::bayer_method)));
00458
00459 __min__.auto_brightness = 0;
00460
00461 __max__.auto_brightness = 4;
00462
00463 __default__.auto_brightness = 1;
00464
00465 __param_descriptions__.push_back(Camera1394Config::AbstractParamDescriptionConstPtr(new Camera1394Config::ParamDescription<int>("auto_brightness", "int", 0, "Brightness control state.", "{'enum_description': 'Feature control states', 'enum': [{'srcline': 177, 'description': 'Use fixed value', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const int', 'value': 0, 'ctype': 'int', 'type': 'int', 'name': 'Off'}, {'srcline': 178, 'description': 'Query current values', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const int', 'value': 1, 'ctype': 'int', 'type': 'int', 'name': 'Query'}, {'srcline': 179, 'description': 'Camera sets continuously', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const int', 'value': 2, 'ctype': 'int', 'type': 'int', 'name': 'Auto'}, {'srcline': 180, 'description': 'Use explicit value', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const int', 'value': 3, 'ctype': 'int', 'type': 'int', 'name': 'Manual'}, {'srcline': 181, 'description': 'Camera sets once', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const int', 'value': 4, 'ctype': 'int', 'type': 'int', 'name': 'OnePush'}, {'srcline': 182, 'description': 'Feature not available', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const int', 'value': 5, 'ctype': 'int', 'type': 'int', 'name': 'None'}]}", &Camera1394Config::auto_brightness)));
00466
00467 __min__.brightness = 0.0;
00468
00469 __max__.brightness = 4095.0;
00470
00471 __default__.brightness = 0.0;
00472
00473 __param_descriptions__.push_back(Camera1394Config::AbstractParamDescriptionConstPtr(new Camera1394Config::ParamDescription<double>("brightness", "double", 0, "Black level offset.", "", &Camera1394Config::brightness)));
00474
00475 __min__.auto_exposure = 0;
00476
00477 __max__.auto_exposure = 4;
00478
00479 __default__.auto_exposure = 1;
00480
00481 __param_descriptions__.push_back(Camera1394Config::AbstractParamDescriptionConstPtr(new Camera1394Config::ParamDescription<int>("auto_exposure", "int", 0, "Combined Gain, Iris & Shutter control.", "{'enum_description': 'Feature control states', 'enum': [{'srcline': 177, 'description': 'Use fixed value', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const int', 'value': 0, 'ctype': 'int', 'type': 'int', 'name': 'Off'}, {'srcline': 178, 'description': 'Query current values', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const int', 'value': 1, 'ctype': 'int', 'type': 'int', 'name': 'Query'}, {'srcline': 179, 'description': 'Camera sets continuously', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const int', 'value': 2, 'ctype': 'int', 'type': 'int', 'name': 'Auto'}, {'srcline': 180, 'description': 'Use explicit value', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const int', 'value': 3, 'ctype': 'int', 'type': 'int', 'name': 'Manual'}, {'srcline': 181, 'description': 'Camera sets once', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const int', 'value': 4, 'ctype': 'int', 'type': 'int', 'name': 'OnePush'}, {'srcline': 182, 'description': 'Feature not available', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const int', 'value': 5, 'ctype': 'int', 'type': 'int', 'name': 'None'}]}", &Camera1394Config::auto_exposure)));
00482
00483 __min__.exposure = -10.0;
00484
00485 __max__.exposure = 4095.0;
00486
00487 __default__.exposure = 0.0;
00488
00489 __param_descriptions__.push_back(Camera1394Config::AbstractParamDescriptionConstPtr(new Camera1394Config::ParamDescription<double>("exposure", "double", 0, "Auto exposure value (like contrast).", "", &Camera1394Config::exposure)));
00490
00491 __min__.auto_focus = 0;
00492
00493 __max__.auto_focus = 4;
00494
00495 __default__.auto_focus = 1;
00496
00497 __param_descriptions__.push_back(Camera1394Config::AbstractParamDescriptionConstPtr(new Camera1394Config::ParamDescription<int>("auto_focus", "int", 0, "Focus control state.", "{'enum_description': 'Feature control states', 'enum': [{'srcline': 177, 'description': 'Use fixed value', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const int', 'value': 0, 'ctype': 'int', 'type': 'int', 'name': 'Off'}, {'srcline': 178, 'description': 'Query current values', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const int', 'value': 1, 'ctype': 'int', 'type': 'int', 'name': 'Query'}, {'srcline': 179, 'description': 'Camera sets continuously', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const int', 'value': 2, 'ctype': 'int', 'type': 'int', 'name': 'Auto'}, {'srcline': 180, 'description': 'Use explicit value', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const int', 'value': 3, 'ctype': 'int', 'type': 'int', 'name': 'Manual'}, {'srcline': 181, 'description': 'Camera sets once', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const int', 'value': 4, 'ctype': 'int', 'type': 'int', 'name': 'OnePush'}, {'srcline': 182, 'description': 'Feature not available', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const int', 'value': 5, 'ctype': 'int', 'type': 'int', 'name': 'None'}]}", &Camera1394Config::auto_focus)));
00498
00499 __min__.focus = 0.0;
00500
00501 __max__.focus = 4095.0;
00502
00503 __default__.focus = 0.0;
00504
00505 __param_descriptions__.push_back(Camera1394Config::AbstractParamDescriptionConstPtr(new Camera1394Config::ParamDescription<double>("focus", "double", 0, "Focus control.", "", &Camera1394Config::focus)));
00506
00507 __min__.auto_gain = 0;
00508
00509 __max__.auto_gain = 4;
00510
00511 __default__.auto_gain = 1;
00512
00513 __param_descriptions__.push_back(Camera1394Config::AbstractParamDescriptionConstPtr(new Camera1394Config::ParamDescription<int>("auto_gain", "int", 0, "Gain control state.", "{'enum_description': 'Feature control states', 'enum': [{'srcline': 177, 'description': 'Use fixed value', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const int', 'value': 0, 'ctype': 'int', 'type': 'int', 'name': 'Off'}, {'srcline': 178, 'description': 'Query current values', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const int', 'value': 1, 'ctype': 'int', 'type': 'int', 'name': 'Query'}, {'srcline': 179, 'description': 'Camera sets continuously', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const int', 'value': 2, 'ctype': 'int', 'type': 'int', 'name': 'Auto'}, {'srcline': 180, 'description': 'Use explicit value', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const int', 'value': 3, 'ctype': 'int', 'type': 'int', 'name': 'Manual'}, {'srcline': 181, 'description': 'Camera sets once', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const int', 'value': 4, 'ctype': 'int', 'type': 'int', 'name': 'OnePush'}, {'srcline': 182, 'description': 'Feature not available', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const int', 'value': 5, 'ctype': 'int', 'type': 'int', 'name': 'None'}]}", &Camera1394Config::auto_gain)));
00514
00515 __min__.gain = -10.0;
00516
00517 __max__.gain = 4095.0;
00518
00519 __default__.gain = 0.0;
00520
00521 __param_descriptions__.push_back(Camera1394Config::AbstractParamDescriptionConstPtr(new Camera1394Config::ParamDescription<double>("gain", "double", 0, "Relative circuit gain.", "", &Camera1394Config::gain)));
00522
00523 __min__.auto_gamma = 0;
00524
00525 __max__.auto_gamma = 4;
00526
00527 __default__.auto_gamma = 1;
00528
00529 __param_descriptions__.push_back(Camera1394Config::AbstractParamDescriptionConstPtr(new Camera1394Config::ParamDescription<int>("auto_gamma", "int", 0, "Gamma control state.", "{'enum_description': 'Feature control states', 'enum': [{'srcline': 177, 'description': 'Use fixed value', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const int', 'value': 0, 'ctype': 'int', 'type': 'int', 'name': 'Off'}, {'srcline': 178, 'description': 'Query current values', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const int', 'value': 1, 'ctype': 'int', 'type': 'int', 'name': 'Query'}, {'srcline': 179, 'description': 'Camera sets continuously', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const int', 'value': 2, 'ctype': 'int', 'type': 'int', 'name': 'Auto'}, {'srcline': 180, 'description': 'Use explicit value', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const int', 'value': 3, 'ctype': 'int', 'type': 'int', 'name': 'Manual'}, {'srcline': 181, 'description': 'Camera sets once', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const int', 'value': 4, 'ctype': 'int', 'type': 'int', 'name': 'OnePush'}, {'srcline': 182, 'description': 'Feature not available', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const int', 'value': 5, 'ctype': 'int', 'type': 'int', 'name': 'None'}]}", &Camera1394Config::auto_gamma)));
00530
00531 __min__.gamma = 0.0;
00532
00533 __max__.gamma = 10.0;
00534
00535 __default__.gamma = 2.2;
00536
00537 __param_descriptions__.push_back(Camera1394Config::AbstractParamDescriptionConstPtr(new Camera1394Config::ParamDescription<double>("gamma", "double", 0, "Gamma expansion exponent.", "", &Camera1394Config::gamma)));
00538
00539 __min__.auto_hue = 0;
00540
00541 __max__.auto_hue = 4;
00542
00543 __default__.auto_hue = 1;
00544
00545 __param_descriptions__.push_back(Camera1394Config::AbstractParamDescriptionConstPtr(new Camera1394Config::ParamDescription<int>("auto_hue", "int", 0, "Hue control state.", "{'enum_description': 'Feature control states', 'enum': [{'srcline': 177, 'description': 'Use fixed value', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const int', 'value': 0, 'ctype': 'int', 'type': 'int', 'name': 'Off'}, {'srcline': 178, 'description': 'Query current values', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const int', 'value': 1, 'ctype': 'int', 'type': 'int', 'name': 'Query'}, {'srcline': 179, 'description': 'Camera sets continuously', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const int', 'value': 2, 'ctype': 'int', 'type': 'int', 'name': 'Auto'}, {'srcline': 180, 'description': 'Use explicit value', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const int', 'value': 3, 'ctype': 'int', 'type': 'int', 'name': 'Manual'}, {'srcline': 181, 'description': 'Camera sets once', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const int', 'value': 4, 'ctype': 'int', 'type': 'int', 'name': 'OnePush'}, {'srcline': 182, 'description': 'Feature not available', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const int', 'value': 5, 'ctype': 'int', 'type': 'int', 'name': 'None'}]}", &Camera1394Config::auto_hue)));
00546
00547 __min__.hue = 0.0;
00548
00549 __max__.hue = 4095.0;
00550
00551 __default__.hue = 0.0;
00552
00553 __param_descriptions__.push_back(Camera1394Config::AbstractParamDescriptionConstPtr(new Camera1394Config::ParamDescription<double>("hue", "double", 0, "Color phase.", "", &Camera1394Config::hue)));
00554
00555 __min__.auto_iris = 0;
00556
00557 __max__.auto_iris = 4;
00558
00559 __default__.auto_iris = 1;
00560
00561 __param_descriptions__.push_back(Camera1394Config::AbstractParamDescriptionConstPtr(new Camera1394Config::ParamDescription<int>("auto_iris", "int", 0, "Iris control state.", "{'enum_description': 'Feature control states', 'enum': [{'srcline': 177, 'description': 'Use fixed value', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const int', 'value': 0, 'ctype': 'int', 'type': 'int', 'name': 'Off'}, {'srcline': 178, 'description': 'Query current values', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const int', 'value': 1, 'ctype': 'int', 'type': 'int', 'name': 'Query'}, {'srcline': 179, 'description': 'Camera sets continuously', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const int', 'value': 2, 'ctype': 'int', 'type': 'int', 'name': 'Auto'}, {'srcline': 180, 'description': 'Use explicit value', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const int', 'value': 3, 'ctype': 'int', 'type': 'int', 'name': 'Manual'}, {'srcline': 181, 'description': 'Camera sets once', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const int', 'value': 4, 'ctype': 'int', 'type': 'int', 'name': 'OnePush'}, {'srcline': 182, 'description': 'Feature not available', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const int', 'value': 5, 'ctype': 'int', 'type': 'int', 'name': 'None'}]}", &Camera1394Config::auto_iris)));
00562
00563 __min__.iris = 0.0;
00564
00565 __max__.iris = 4095.0;
00566
00567 __default__.iris = 8.0;
00568
00569 __param_descriptions__.push_back(Camera1394Config::AbstractParamDescriptionConstPtr(new Camera1394Config::ParamDescription<double>("iris", "double", 0, "Iris control.", "", &Camera1394Config::iris)));
00570
00571 __min__.auto_saturation = 0;
00572
00573 __max__.auto_saturation = 4;
00574
00575 __default__.auto_saturation = 1;
00576
00577 __param_descriptions__.push_back(Camera1394Config::AbstractParamDescriptionConstPtr(new Camera1394Config::ParamDescription<int>("auto_saturation", "int", 0, "Saturation control state.", "{'enum_description': 'Feature control states', 'enum': [{'srcline': 177, 'description': 'Use fixed value', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const int', 'value': 0, 'ctype': 'int', 'type': 'int', 'name': 'Off'}, {'srcline': 178, 'description': 'Query current values', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const int', 'value': 1, 'ctype': 'int', 'type': 'int', 'name': 'Query'}, {'srcline': 179, 'description': 'Camera sets continuously', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const int', 'value': 2, 'ctype': 'int', 'type': 'int', 'name': 'Auto'}, {'srcline': 180, 'description': 'Use explicit value', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const int', 'value': 3, 'ctype': 'int', 'type': 'int', 'name': 'Manual'}, {'srcline': 181, 'description': 'Camera sets once', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const int', 'value': 4, 'ctype': 'int', 'type': 'int', 'name': 'OnePush'}, {'srcline': 182, 'description': 'Feature not available', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const int', 'value': 5, 'ctype': 'int', 'type': 'int', 'name': 'None'}]}", &Camera1394Config::auto_saturation)));
00578
00579 __min__.saturation = 0.0;
00580
00581 __max__.saturation = 4095.0;
00582
00583 __default__.saturation = 1.0;
00584
00585 __param_descriptions__.push_back(Camera1394Config::AbstractParamDescriptionConstPtr(new Camera1394Config::ParamDescription<double>("saturation", "double", 0, "Color saturation.", "", &Camera1394Config::saturation)));
00586
00587 __min__.auto_sharpness = 0;
00588
00589 __max__.auto_sharpness = 4;
00590
00591 __default__.auto_sharpness = 1;
00592
00593 __param_descriptions__.push_back(Camera1394Config::AbstractParamDescriptionConstPtr(new Camera1394Config::ParamDescription<int>("auto_sharpness", "int", 0, "Sharpness control state.", "{'enum_description': 'Feature control states', 'enum': [{'srcline': 177, 'description': 'Use fixed value', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const int', 'value': 0, 'ctype': 'int', 'type': 'int', 'name': 'Off'}, {'srcline': 178, 'description': 'Query current values', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const int', 'value': 1, 'ctype': 'int', 'type': 'int', 'name': 'Query'}, {'srcline': 179, 'description': 'Camera sets continuously', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const int', 'value': 2, 'ctype': 'int', 'type': 'int', 'name': 'Auto'}, {'srcline': 180, 'description': 'Use explicit value', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const int', 'value': 3, 'ctype': 'int', 'type': 'int', 'name': 'Manual'}, {'srcline': 181, 'description': 'Camera sets once', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const int', 'value': 4, 'ctype': 'int', 'type': 'int', 'name': 'OnePush'}, {'srcline': 182, 'description': 'Feature not available', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const int', 'value': 5, 'ctype': 'int', 'type': 'int', 'name': 'None'}]}", &Camera1394Config::auto_sharpness)));
00594
00595 __min__.sharpness = 0.0;
00596
00597 __max__.sharpness = 4095.0;
00598
00599 __default__.sharpness = 1.0;
00600
00601 __param_descriptions__.push_back(Camera1394Config::AbstractParamDescriptionConstPtr(new Camera1394Config::ParamDescription<double>("sharpness", "double", 0, "Image sharpness.", "", &Camera1394Config::sharpness)));
00602
00603 __min__.auto_shutter = 0;
00604
00605 __max__.auto_shutter = 4;
00606
00607 __default__.auto_shutter = 1;
00608
00609 __param_descriptions__.push_back(Camera1394Config::AbstractParamDescriptionConstPtr(new Camera1394Config::ParamDescription<int>("auto_shutter", "int", 0, "Shutter control state.", "{'enum_description': 'Feature control states', 'enum': [{'srcline': 177, 'description': 'Use fixed value', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const int', 'value': 0, 'ctype': 'int', 'type': 'int', 'name': 'Off'}, {'srcline': 178, 'description': 'Query current values', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const int', 'value': 1, 'ctype': 'int', 'type': 'int', 'name': 'Query'}, {'srcline': 179, 'description': 'Camera sets continuously', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const int', 'value': 2, 'ctype': 'int', 'type': 'int', 'name': 'Auto'}, {'srcline': 180, 'description': 'Use explicit value', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const int', 'value': 3, 'ctype': 'int', 'type': 'int', 'name': 'Manual'}, {'srcline': 181, 'description': 'Camera sets once', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const int', 'value': 4, 'ctype': 'int', 'type': 'int', 'name': 'OnePush'}, {'srcline': 182, 'description': 'Feature not available', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const int', 'value': 5, 'ctype': 'int', 'type': 'int', 'name': 'None'}]}", &Camera1394Config::auto_shutter)));
00610
00611 __min__.shutter = 0.0;
00612
00613 __max__.shutter = 4095.0;
00614
00615 __default__.shutter = 1.0;
00616
00617 __param_descriptions__.push_back(Camera1394Config::AbstractParamDescriptionConstPtr(new Camera1394Config::ParamDescription<double>("shutter", "double", 0, "Shutter speed.", "", &Camera1394Config::shutter)));
00618
00619 __min__.auto_white_balance = 0;
00620
00621 __max__.auto_white_balance = 4;
00622
00623 __default__.auto_white_balance = 1;
00624
00625 __param_descriptions__.push_back(Camera1394Config::AbstractParamDescriptionConstPtr(new Camera1394Config::ParamDescription<int>("auto_white_balance", "int", 0, "White balance control state.", "{'enum_description': 'Feature control states', 'enum': [{'srcline': 177, 'description': 'Use fixed value', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const int', 'value': 0, 'ctype': 'int', 'type': 'int', 'name': 'Off'}, {'srcline': 178, 'description': 'Query current values', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const int', 'value': 1, 'ctype': 'int', 'type': 'int', 'name': 'Query'}, {'srcline': 179, 'description': 'Camera sets continuously', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const int', 'value': 2, 'ctype': 'int', 'type': 'int', 'name': 'Auto'}, {'srcline': 180, 'description': 'Use explicit value', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const int', 'value': 3, 'ctype': 'int', 'type': 'int', 'name': 'Manual'}, {'srcline': 181, 'description': 'Camera sets once', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const int', 'value': 4, 'ctype': 'int', 'type': 'int', 'name': 'OnePush'}, {'srcline': 182, 'description': 'Feature not available', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const int', 'value': 5, 'ctype': 'int', 'type': 'int', 'name': 'None'}]}", &Camera1394Config::auto_white_balance)));
00626
00627 __min__.white_balance_BU = 0.0;
00628
00629 __max__.white_balance_BU = 4095.0;
00630
00631 __default__.white_balance_BU = 0.0;
00632
00633 __param_descriptions__.push_back(Camera1394Config::AbstractParamDescriptionConstPtr(new Camera1394Config::ParamDescription<double>("white_balance_BU", "double", 0, "Blue or U component of white balance.", "", &Camera1394Config::white_balance_BU)));
00634
00635 __min__.white_balance_RV = 0.0;
00636
00637 __max__.white_balance_RV = 4095.0;
00638
00639 __default__.white_balance_RV = 0.0;
00640
00641 __param_descriptions__.push_back(Camera1394Config::AbstractParamDescriptionConstPtr(new Camera1394Config::ParamDescription<double>("white_balance_RV", "double", 0, "Red or V component of white balance.", "", &Camera1394Config::white_balance_RV)));
00642
00643 __min__.auto_zoom = 0;
00644
00645 __max__.auto_zoom = 4;
00646
00647 __default__.auto_zoom = 1;
00648
00649 __param_descriptions__.push_back(Camera1394Config::AbstractParamDescriptionConstPtr(new Camera1394Config::ParamDescription<int>("auto_zoom", "int", 0, "Zoom control state.", "{'enum_description': 'Feature control states', 'enum': [{'srcline': 177, 'description': 'Use fixed value', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const int', 'value': 0, 'ctype': 'int', 'type': 'int', 'name': 'Off'}, {'srcline': 178, 'description': 'Query current values', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const int', 'value': 1, 'ctype': 'int', 'type': 'int', 'name': 'Query'}, {'srcline': 179, 'description': 'Camera sets continuously', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const int', 'value': 2, 'ctype': 'int', 'type': 'int', 'name': 'Auto'}, {'srcline': 180, 'description': 'Use explicit value', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const int', 'value': 3, 'ctype': 'int', 'type': 'int', 'name': 'Manual'}, {'srcline': 181, 'description': 'Camera sets once', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const int', 'value': 4, 'ctype': 'int', 'type': 'int', 'name': 'OnePush'}, {'srcline': 182, 'description': 'Feature not available', 'srcfile': '../cfg/Camera1394.cfg', 'cconsttype': 'const int', 'value': 5, 'ctype': 'int', 'type': 'int', 'name': 'None'}]}", &Camera1394Config::auto_zoom)));
00650
00651 __min__.zoom = 0.0;
00652
00653 __max__.zoom = 4095.0;
00654
00655 __default__.zoom = 0.0;
00656
00657 __param_descriptions__.push_back(Camera1394Config::AbstractParamDescriptionConstPtr(new Camera1394Config::ParamDescription<double>("zoom", "double", 0, "Zoom control.", "", &Camera1394Config::zoom)));
00658
00659 __min__.use_ros_time = 0;
00660
00661 __max__.use_ros_time = 1;
00662
00663 __default__.use_ros_time = 0;
00664
00665 __param_descriptions__.push_back(Camera1394Config::AbstractParamDescriptionConstPtr(new Camera1394Config::ParamDescription<bool>("use_ros_time", "bool", 3, "Timestamp Image and CameraInfo using ros::Time::now()", "", &Camera1394Config::use_ros_time)));
00666
00667
00668 for (std::vector<Camera1394Config::AbstractParamDescriptionConstPtr>::const_iterator i = __param_descriptions__.begin(); i != __param_descriptions__.end(); i++)
00669 __description_message__.parameters.push_back(**i);
00670 __max__.__toMessage__(__description_message__.max, __param_descriptions__);
00671 __min__.__toMessage__(__description_message__.min, __param_descriptions__);
00672 __default__.__toMessage__(__description_message__.dflt, __param_descriptions__);
00673 }
00674 std::vector<Camera1394Config::AbstractParamDescriptionConstPtr> __param_descriptions__;
00675 Camera1394Config __max__;
00676 Camera1394Config __min__;
00677 Camera1394Config __default__;
00678 dynamic_reconfigure::ConfigDescription __description_message__;
00679 static const Camera1394ConfigStatics *get_instance()
00680 {
00681
00682
00683
00684
00685 static Camera1394ConfigStatics instance;
00686 return &instance;
00687 }
00688 };
00689
00690 inline const dynamic_reconfigure::ConfigDescription &Camera1394Config::__getDescriptionMessage__()
00691 {
00692 return __get_statics__()->__description_message__;
00693 }
00694
00695 inline const Camera1394Config &Camera1394Config::__getDefault__()
00696 {
00697 return __get_statics__()->__default__;
00698 }
00699
00700 inline const Camera1394Config &Camera1394Config::__getMax__()
00701 {
00702 return __get_statics__()->__max__;
00703 }
00704
00705 inline const Camera1394Config &Camera1394Config::__getMin__()
00706 {
00707 return __get_statics__()->__min__;
00708 }
00709
00710 inline const std::vector<Camera1394Config::AbstractParamDescriptionConstPtr> &Camera1394Config::__getParamDescriptions__()
00711 {
00712 return __get_statics__()->__param_descriptions__;
00713 }
00714
00715 inline const Camera1394ConfigStatics *Camera1394Config::__get_statics__()
00716 {
00717 const static Camera1394ConfigStatics *statics;
00718
00719 if (statics)
00720 return statics;
00721
00722 boost::mutex::scoped_lock lock(dynamic_reconfigure::__init_mutex__);
00723
00724 if (statics)
00725 return statics;
00726
00727 statics = Camera1394ConfigStatics::get_instance();
00728
00729 return statics;
00730 }
00731
00732
00733 const char * const Camera1394_Format0_Mode0 = "160x120_yuv444";
00734
00735 const char * const Camera1394_Format0_Mode1 = "320x240_yuv422";
00736
00737 const char * const Camera1394_Format0_Mode2 = "640x480_yuv411";
00738
00739 const char * const Camera1394_Format0_Mode3 = "640x480_yuv422";
00740
00741 const char * const Camera1394_Format0_Mode4 = "640x480_rgb8";
00742
00743 const char * const Camera1394_Format0_Mode5 = "640x480_mono8";
00744
00745 const char * const Camera1394_Format0_Mode6 = "640x480_mono16";
00746
00747 const char * const Camera1394_Format1_Mode0 = "800x600_yuv422";
00748
00749 const char * const Camera1394_Format1_Mode1 = "800x600_rgb8";
00750
00751 const char * const Camera1394_Format1_Mode2 = "800x600_mono8";
00752
00753 const char * const Camera1394_Format1_Mode6 = "800x600_mono16";
00754
00755 const char * const Camera1394_Format1_Mode3 = "1024x768_yuv422";
00756
00757 const char * const Camera1394_Format1_Mode4 = "1024x768_rgb8";
00758
00759 const char * const Camera1394_Format1_Mode5 = "1024x768_mono8";
00760
00761 const char * const Camera1394_Format1_Mode7 = "1024x768_mono16";
00762
00763 const char * const Camera1394_Format2_Mode0 = "1280x960_yuv422";
00764
00765 const char * const Camera1394_Format2_Mode1 = "1280x960_rgb8";
00766
00767 const char * const Camera1394_Format2_Mode2 = "1280x960_mono8";
00768
00769 const char * const Camera1394_Format2_Mode6 = "1280x960_mono16";
00770
00771 const char * const Camera1394_Format2_Mode3 = "1600x1200_yuv422";
00772
00773 const char * const Camera1394_Format2_Mode4 = "1600x1200_rgb8";
00774
00775 const char * const Camera1394_Format2_Mode5 = "1600x1200_mono8";
00776
00777 const char * const Camera1394_Format2_Mode7 = "1600x1200_mono16";
00778
00779 const char * const Camera1394_Format7_Mode0 = "format7_mode0";
00780
00781 const char * const Camera1394_Format7_Mode1 = "format7_mode1";
00782
00783 const char * const Camera1394_Format7_Mode2 = "format7_mode2";
00784
00785 const char * const Camera1394_Format7_Mode3 = "format7_mode3";
00786
00787 const char * const Camera1394_Format7_Mode4 = "format7_mode4";
00788
00789 const char * const Camera1394_Format7_Mode5 = "format7_mode5";
00790
00791 const char * const Camera1394_Format7_Mode6 = "format7_mode6";
00792
00793 const char * const Camera1394_Format7_Mode7 = "format7_mode7";
00794
00795 const char * const Camera1394_mono8 = "mono8";
00796
00797 const char * const Camera1394_mono16 = "mono16";
00798
00799 const char * const Camera1394_mono16s = "mono16s";
00800
00801 const char * const Camera1394_raw8 = "raw8";
00802
00803 const char * const Camera1394_raw16 = "raw16";
00804
00805 const char * const Camera1394_rgb8 = "rgb8";
00806
00807 const char * const Camera1394_rgb16 = "rgb16";
00808
00809 const char * const Camera1394_rgb16s = "rgb16s";
00810
00811 const char * const Camera1394_yuv411 = "yuv411";
00812
00813 const char * const Camera1394_yuv422 = "yuv422";
00814
00815 const char * const Camera1394_yuv444 = "yuv444";
00816
00817 const char * const Camera1394_none = "";
00818
00819 const char * const Camera1394_rggb = "rggb";
00820
00821 const char * const Camera1394_gbrg = "gbrg";
00822
00823 const char * const Camera1394_grbg = "grbg";
00824
00825 const char * const Camera1394_bggr = "bggr";
00826
00827 const char * const Camera1394_image_proc = "";
00828
00829 const char * const Camera1394_DownSample = "DownSample";
00830
00831 const char * const Camera1394_Simple = "Simple";
00832
00833 const char * const Camera1394_Bilinear = "Bilinear";
00834
00835 const char * const Camera1394_HQ = "HQ";
00836
00837 const char * const Camera1394_VNG = "VNG";
00838
00839 const char * const Camera1394_AHD = "AHD";
00840
00841 const int Camera1394_Off = 0;
00842
00843 const int Camera1394_Query = 1;
00844
00845 const int Camera1394_Auto = 2;
00846
00847 const int Camera1394_Manual = 3;
00848
00849 const int Camera1394_OnePush = 4;
00850
00851 const int Camera1394_None = 5;
00852 }
00853
00854 #endif // __CAMERA1394RECONFIGURATOR_H__