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 __gazebo_plugins__CAMERASYNCHRONIZERCONFIG_H__
00048 #define __gazebo_plugins__CAMERASYNCHRONIZERCONFIG_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 gazebo_plugins
00058 {
00059 class CameraSynchronizerConfigStatics;
00060
00061 class CameraSynchronizerConfig
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(CameraSynchronizerConfig &config, const CameraSynchronizerConfig &max, const CameraSynchronizerConfig &min) const = 0;
00078 virtual void calcLevel(uint32_t &level, const CameraSynchronizerConfig &config1, const CameraSynchronizerConfig &config2) const = 0;
00079 virtual void fromServer(const ros::NodeHandle &nh, CameraSynchronizerConfig &config) const = 0;
00080 virtual void toServer(const ros::NodeHandle &nh, const CameraSynchronizerConfig &config) const = 0;
00081 virtual bool fromMessage(const dynamic_reconfigure::Config &msg, CameraSynchronizerConfig &config) const = 0;
00082 virtual void toMessage(dynamic_reconfigure::Config &msg, const CameraSynchronizerConfig &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 CameraSynchronizerConfig::* f) :
00094 AbstractParamDescription(name, type, level, description, edit_method),
00095 field(f)
00096 {}
00097
00098 T (CameraSynchronizerConfig::* field);
00099
00100 virtual void clamp(CameraSynchronizerConfig &config, const CameraSynchronizerConfig &max, const CameraSynchronizerConfig &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 CameraSynchronizerConfig &config1, const CameraSynchronizerConfig &config2) const
00110 {
00111 if (config1.*field != config2.*field)
00112 comb_level |= level;
00113 }
00114
00115 virtual void fromServer(const ros::NodeHandle &nh, CameraSynchronizerConfig &config) const
00116 {
00117 nh.getParam(name, config.*field);
00118 }
00119
00120 virtual void toServer(const ros::NodeHandle &nh, const CameraSynchronizerConfig &config) const
00121 {
00122 nh.setParam(name, config.*field);
00123 }
00124
00125 virtual bool fromMessage(const dynamic_reconfigure::Config &msg, CameraSynchronizerConfig &config) const
00126 {
00127 return dynamic_reconfigure::ConfigTools::getParameter(msg, name, config.*field);
00128 }
00129
00130 virtual void toMessage(dynamic_reconfigure::Config &msg, const CameraSynchronizerConfig &config) const
00131 {
00132 dynamic_reconfigure::ConfigTools::appendParameter(msg, name, config.*field);
00133 }
00134 };
00135
00136
00137 double projector_rate;
00138
00139 double projector_pulse_length;
00140
00141 double projector_pulse_shift;
00142
00143 int projector_mode;
00144
00145 bool prosilica_projector_inhibit;
00146
00147 double stereo_rate;
00148
00149 int wide_stereo_trig_mode;
00150
00151 int narrow_stereo_trig_mode;
00152
00153 double forearm_r_rate;
00154
00155 int forearm_r_trig_mode;
00156
00157 double forearm_l_rate;
00158
00159 int forearm_l_trig_mode;
00160
00161 double projector_tweak;
00162
00163 bool camera_reset;
00164
00165
00166 bool __fromMessage__(dynamic_reconfigure::Config &msg)
00167 {
00168 const std::vector<AbstractParamDescriptionConstPtr> &__param_descriptions__ = __getParamDescriptions__();
00169 int count = 0;
00170 for (std::vector<AbstractParamDescriptionConstPtr>::const_iterator i = __param_descriptions__.begin(); i != __param_descriptions__.end(); i++)
00171 if ((*i)->fromMessage(msg, *this))
00172 count++;
00173 if (count != dynamic_reconfigure::ConfigTools::size(msg))
00174 {
00175 ROS_ERROR("CameraSynchronizerConfig::__fromMessage__ called with an unexpected parameter.");
00176 ROS_ERROR("Booleans:");
00177 for (unsigned int i = 0; i < msg.bools.size(); i++)
00178 ROS_ERROR(" %s", msg.bools[i].name.c_str());
00179 ROS_ERROR("Integers:");
00180 for (unsigned int i = 0; i < msg.ints.size(); i++)
00181 ROS_ERROR(" %s", msg.ints[i].name.c_str());
00182 ROS_ERROR("Doubles:");
00183 for (unsigned int i = 0; i < msg.doubles.size(); i++)
00184 ROS_ERROR(" %s", msg.doubles[i].name.c_str());
00185 ROS_ERROR("Strings:");
00186 for (unsigned int i = 0; i < msg.strs.size(); i++)
00187 ROS_ERROR(" %s", msg.strs[i].name.c_str());
00188
00189
00190 return false;
00191 }
00192 return true;
00193 }
00194
00195
00196
00197 void __toMessage__(dynamic_reconfigure::Config &msg, const std::vector<AbstractParamDescriptionConstPtr> &__param_descriptions__) const
00198 {
00199 dynamic_reconfigure::ConfigTools::clear(msg);
00200 for (std::vector<AbstractParamDescriptionConstPtr>::const_iterator i = __param_descriptions__.begin(); i != __param_descriptions__.end(); i++)
00201 (*i)->toMessage(msg, *this);
00202 }
00203
00204 void __toMessage__(dynamic_reconfigure::Config &msg) const
00205 {
00206 const std::vector<AbstractParamDescriptionConstPtr> &__param_descriptions__ = __getParamDescriptions__();
00207 __toMessage__(msg, __param_descriptions__);
00208 }
00209
00210 void __toServer__(const ros::NodeHandle &nh) const
00211 {
00212 const std::vector<AbstractParamDescriptionConstPtr> &__param_descriptions__ = __getParamDescriptions__();
00213 for (std::vector<AbstractParamDescriptionConstPtr>::const_iterator i = __param_descriptions__.begin(); i != __param_descriptions__.end(); i++)
00214 (*i)->toServer(nh, *this);
00215 }
00216
00217 void __fromServer__(const ros::NodeHandle &nh)
00218 {
00219 const std::vector<AbstractParamDescriptionConstPtr> &__param_descriptions__ = __getParamDescriptions__();
00220 for (std::vector<AbstractParamDescriptionConstPtr>::const_iterator i = __param_descriptions__.begin(); i != __param_descriptions__.end(); i++)
00221 (*i)->fromServer(nh, *this);
00222 }
00223
00224 void __clamp__()
00225 {
00226 const std::vector<AbstractParamDescriptionConstPtr> &__param_descriptions__ = __getParamDescriptions__();
00227 const CameraSynchronizerConfig &__max__ = __getMax__();
00228 const CameraSynchronizerConfig &__min__ = __getMin__();
00229 for (std::vector<AbstractParamDescriptionConstPtr>::const_iterator i = __param_descriptions__.begin(); i != __param_descriptions__.end(); i++)
00230 (*i)->clamp(*this, __max__, __min__);
00231 }
00232
00233 uint32_t __level__(const CameraSynchronizerConfig &config) const
00234 {
00235 const std::vector<AbstractParamDescriptionConstPtr> &__param_descriptions__ = __getParamDescriptions__();
00236 uint32_t level = 0;
00237 for (std::vector<AbstractParamDescriptionConstPtr>::const_iterator i = __param_descriptions__.begin(); i != __param_descriptions__.end(); i++)
00238 (*i)->calcLevel(level, config, *this);
00239 return level;
00240 }
00241
00242 static const dynamic_reconfigure::ConfigDescription &__getDescriptionMessage__();
00243 static const CameraSynchronizerConfig &__getDefault__();
00244 static const CameraSynchronizerConfig &__getMax__();
00245 static const CameraSynchronizerConfig &__getMin__();
00246 static const std::vector<AbstractParamDescriptionConstPtr> &__getParamDescriptions__();
00247
00248 private:
00249 static const CameraSynchronizerConfigStatics *__get_statics__();
00250 };
00251
00252 template <>
00253 inline void CameraSynchronizerConfig::ParamDescription<std::string>::clamp(CameraSynchronizerConfig &config, const CameraSynchronizerConfig &max, const CameraSynchronizerConfig &min) const
00254 {
00255 return;
00256 }
00257
00258 class CameraSynchronizerConfigStatics
00259 {
00260 friend class CameraSynchronizerConfig;
00261
00262 CameraSynchronizerConfigStatics()
00263 {
00264
00265 __min__.projector_rate = 40.0;
00266
00267 __max__.projector_rate = 120.0;
00268
00269 __default__.projector_rate = 60.0;
00270
00271 __param_descriptions__.push_back(CameraSynchronizerConfig::AbstractParamDescriptionConstPtr(new CameraSynchronizerConfig::ParamDescription<double>("projector_rate", "double", 31, "Projector pulse frequency in Hz.", "", &CameraSynchronizerConfig::projector_rate)));
00272
00273 __min__.projector_pulse_length = 0.001;
00274
00275 __max__.projector_pulse_length = 0.002;
00276
00277 __default__.projector_pulse_length = 0.002;
00278
00279 __param_descriptions__.push_back(CameraSynchronizerConfig::AbstractParamDescriptionConstPtr(new CameraSynchronizerConfig::ParamDescription<double>("projector_pulse_length", "double", 31, "Length of the projector pulses in s. At high currents the hardware may limit the pulse length.", "", &CameraSynchronizerConfig::projector_pulse_length)));
00280
00281 __min__.projector_pulse_shift = 0.0;
00282
00283 __max__.projector_pulse_shift = 1.0;
00284
00285 __default__.projector_pulse_shift = 0.0;
00286
00287 __param_descriptions__.push_back(CameraSynchronizerConfig::AbstractParamDescriptionConstPtr(new CameraSynchronizerConfig::ParamDescription<double>("projector_pulse_shift", "double", 31, "How far off-center the intermediate projector pulses are. Zero is on-center, one is touching the following pulse.", "", &CameraSynchronizerConfig::projector_pulse_shift)));
00288
00289 __min__.projector_mode = 1;
00290
00291 __max__.projector_mode = 3;
00292
00293 __default__.projector_mode = 2;
00294
00295 __param_descriptions__.push_back(CameraSynchronizerConfig::AbstractParamDescriptionConstPtr(new CameraSynchronizerConfig::ParamDescription<int>("projector_mode", "int", 31, "Indicates whether the projector should be off, on when in use or on all the time.", "{'enum_description': 'The projectors operating mode.', 'enum': [{'srcline': 55, 'description': 'The projector is always off.', 'srcfile': '../cfg/CameraSynchronizer.cfg', 'cconsttype': 'const int', 'value': 1, 'ctype': 'int', 'type': 'int', 'name': 'ProjectorOff'}, {'srcline': 56, 'description': 'The projector is on if one of the cameras is using it.', 'srcfile': '../cfg/CameraSynchronizer.cfg', 'cconsttype': 'const int', 'value': 2, 'ctype': 'int', 'type': 'int', 'name': 'ProjectorAuto'}, {'srcline': 57, 'description': 'The projector is always on.', 'srcfile': '../cfg/CameraSynchronizer.cfg', 'cconsttype': 'const int', 'value': 3, 'ctype': 'int', 'type': 'int', 'name': 'ProjectorOn'}]}", &CameraSynchronizerConfig::projector_mode)));
00296
00297 __min__.prosilica_projector_inhibit = 0;
00298
00299 __max__.prosilica_projector_inhibit = 1;
00300
00301 __default__.prosilica_projector_inhibit = 0;
00302
00303 __param_descriptions__.push_back(CameraSynchronizerConfig::AbstractParamDescriptionConstPtr(new CameraSynchronizerConfig::ParamDescription<bool>("prosilica_projector_inhibit", "bool", 16, "Indicates if the projector should turn off when the prosilica camera is exposing.", "", &CameraSynchronizerConfig::prosilica_projector_inhibit)));
00304
00305 __min__.stereo_rate = 1.0;
00306
00307 __max__.stereo_rate = 60.0;
00308
00309 __default__.stereo_rate = 30.0;
00310
00311 __param_descriptions__.push_back(CameraSynchronizerConfig::AbstractParamDescriptionConstPtr(new CameraSynchronizerConfig::ParamDescription<double>("stereo_rate", "double", 3, "Indicates the frame rate for both stereo cameras in Hz. (Gets rounded to suitable divisors of projector_rate.)", "", &CameraSynchronizerConfig::stereo_rate)));
00312
00313 __min__.wide_stereo_trig_mode = 2;
00314
00315 __max__.wide_stereo_trig_mode = 4;
00316
00317 __default__.wide_stereo_trig_mode = 4;
00318
00319 __param_descriptions__.push_back(CameraSynchronizerConfig::AbstractParamDescriptionConstPtr(new CameraSynchronizerConfig::ParamDescription<int>("wide_stereo_trig_mode", "int", 3, "Indicates the triggering mode of the wide stereo camera.", "{'enum_description': 'The triggering mode for the wide camera.', 'enum': [{'srcline': 61, 'description': 'The cameras frequency can be set independently of the projector frequency. There is no deterministic phase relation between projector firing and camera triggering.', 'srcfile': '../cfg/CameraSynchronizer.cfg', 'cconsttype': 'const int', 'value': 2, 'ctype': 'int', 'type': 'int', 'name': 'IgnoreProjector'}, {'srcline': 62, 'description': 'The camera always exposes while the projector is on.', 'srcfile': '../cfg/CameraSynchronizer.cfg', 'cconsttype': 'const int', 'value': 3, 'ctype': 'int', 'type': 'int', 'name': 'WithProjector'}, {'srcline': 63, 'description': 'The camera always exposes while the projector is off.', 'srcfile': '../cfg/CameraSynchronizer.cfg', 'cconsttype': 'const int', 'value': 4, 'ctype': 'int', 'type': 'int', 'name': 'WithoutProjector'}]}", &CameraSynchronizerConfig::wide_stereo_trig_mode)));
00320
00321 __min__.narrow_stereo_trig_mode = 2;
00322
00323 __max__.narrow_stereo_trig_mode = 5;
00324
00325 __default__.narrow_stereo_trig_mode = 4;
00326
00327 __param_descriptions__.push_back(CameraSynchronizerConfig::AbstractParamDescriptionConstPtr(new CameraSynchronizerConfig::ParamDescription<int>("narrow_stereo_trig_mode", "int", 3, "Indicates the triggering mode of the narrow stereo camera.", "{'enum_description': 'The triggering mode for the narrow camera.', 'enum': [{'srcline': 61, 'description': 'The cameras frequency can be set independently of the projector frequency. There is no deterministic phase relation between projector firing and camera triggering.', 'srcfile': '../cfg/CameraSynchronizer.cfg', 'cconsttype': 'const int', 'value': 2, 'ctype': 'int', 'type': 'int', 'name': 'IgnoreProjector'}, {'srcline': 62, 'description': 'The camera always exposes while the projector is on.', 'srcfile': '../cfg/CameraSynchronizer.cfg', 'cconsttype': 'const int', 'value': 3, 'ctype': 'int', 'type': 'int', 'name': 'WithProjector'}, {'srcline': 63, 'description': 'The camera always exposes while the projector is off.', 'srcfile': '../cfg/CameraSynchronizer.cfg', 'cconsttype': 'const int', 'value': 4, 'ctype': 'int', 'type': 'int', 'name': 'WithoutProjector'}, {'srcline': 64, 'description': 'The camera alternates between frames with and without the projector.', 'srcfile': '../cfg/CameraSynchronizer.cfg', 'cconsttype': 'const int', 'value': 5, 'ctype': 'int', 'type': 'int', 'name': 'AlternateProjector'}]}", &CameraSynchronizerConfig::narrow_stereo_trig_mode)));
00328
00329 __min__.forearm_r_rate = 1.0;
00330
00331 __max__.forearm_r_rate = 60.0;
00332
00333 __default__.forearm_r_rate = 30.0;
00334
00335 __param_descriptions__.push_back(CameraSynchronizerConfig::AbstractParamDescriptionConstPtr(new CameraSynchronizerConfig::ParamDescription<double>("forearm_r_rate", "double", 4, "Indicates the frame rate for the right forearm camera in Hz. (Gets rounded to suitable divisors of projector_rate.)", "", &CameraSynchronizerConfig::forearm_r_rate)));
00336
00337 __min__.forearm_r_trig_mode = 1;
00338
00339 __max__.forearm_r_trig_mode = 4;
00340
00341 __default__.forearm_r_trig_mode = 1;
00342
00343 __param_descriptions__.push_back(CameraSynchronizerConfig::AbstractParamDescriptionConstPtr(new CameraSynchronizerConfig::ParamDescription<int>("forearm_r_trig_mode", "int", 4, "Indicates the triggering mode of the right forearm camera.", "{'enum_description': 'The triggering mode for a forearm camera.', 'enum': [{'srcline': 60, 'description': 'The camera does not use the trigger input.', 'srcfile': '../cfg/CameraSynchronizer.cfg', 'cconsttype': 'const int', 'value': 1, 'ctype': 'int', 'type': 'int', 'name': 'InternalTrigger'}, {'srcline': 61, 'description': 'The cameras frequency can be set independently of the projector frequency. There is no deterministic phase relation between projector firing and camera triggering.', 'srcfile': '../cfg/CameraSynchronizer.cfg', 'cconsttype': 'const int', 'value': 2, 'ctype': 'int', 'type': 'int', 'name': 'IgnoreProjector'}, {'srcline': 62, 'description': 'The camera always exposes while the projector is on.', 'srcfile': '../cfg/CameraSynchronizer.cfg', 'cconsttype': 'const int', 'value': 3, 'ctype': 'int', 'type': 'int', 'name': 'WithProjector'}, {'srcline': 63, 'description': 'The camera always exposes while the projector is off.', 'srcfile': '../cfg/CameraSynchronizer.cfg', 'cconsttype': 'const int', 'value': 4, 'ctype': 'int', 'type': 'int', 'name': 'WithoutProjector'}]}", &CameraSynchronizerConfig::forearm_r_trig_mode)));
00344
00345 __min__.forearm_l_rate = 1.0;
00346
00347 __max__.forearm_l_rate = 60.0;
00348
00349 __default__.forearm_l_rate = 30.0;
00350
00351 __param_descriptions__.push_back(CameraSynchronizerConfig::AbstractParamDescriptionConstPtr(new CameraSynchronizerConfig::ParamDescription<double>("forearm_l_rate", "double", 8, "Indicates the frame rate for the left forearm camera in Hz. (Gets rounded to suitable divisors of projector_rate.)", "", &CameraSynchronizerConfig::forearm_l_rate)));
00352
00353 __min__.forearm_l_trig_mode = 1;
00354
00355 __max__.forearm_l_trig_mode = 4;
00356
00357 __default__.forearm_l_trig_mode = 1;
00358
00359 __param_descriptions__.push_back(CameraSynchronizerConfig::AbstractParamDescriptionConstPtr(new CameraSynchronizerConfig::ParamDescription<int>("forearm_l_trig_mode", "int", 8, "Indicates the triggering mode of the left forearm camera.", "{'enum_description': 'The triggering mode for a forearm camera.', 'enum': [{'srcline': 60, 'description': 'The camera does not use the trigger input.', 'srcfile': '../cfg/CameraSynchronizer.cfg', 'cconsttype': 'const int', 'value': 1, 'ctype': 'int', 'type': 'int', 'name': 'InternalTrigger'}, {'srcline': 61, 'description': 'The cameras frequency can be set independently of the projector frequency. There is no deterministic phase relation between projector firing and camera triggering.', 'srcfile': '../cfg/CameraSynchronizer.cfg', 'cconsttype': 'const int', 'value': 2, 'ctype': 'int', 'type': 'int', 'name': 'IgnoreProjector'}, {'srcline': 62, 'description': 'The camera always exposes while the projector is on.', 'srcfile': '../cfg/CameraSynchronizer.cfg', 'cconsttype': 'const int', 'value': 3, 'ctype': 'int', 'type': 'int', 'name': 'WithProjector'}, {'srcline': 63, 'description': 'The camera always exposes while the projector is off.', 'srcfile': '../cfg/CameraSynchronizer.cfg', 'cconsttype': 'const int', 'value': 4, 'ctype': 'int', 'type': 'int', 'name': 'WithoutProjector'}]}", &CameraSynchronizerConfig::forearm_l_trig_mode)));
00360
00361 __min__.projector_tweak = -0.1;
00362
00363 __max__.projector_tweak = 0.1;
00364
00365 __default__.projector_tweak = 0.0;
00366
00367 __param_descriptions__.push_back(CameraSynchronizerConfig::AbstractParamDescriptionConstPtr(new CameraSynchronizerConfig::ParamDescription<double>("projector_tweak", "double", 31, "Adds a time shift in seconds to the projector timing. Useful for debugging but not in normal use.", "", &CameraSynchronizerConfig::projector_tweak)));
00368
00369 __min__.camera_reset = 0;
00370
00371 __max__.camera_reset = 1;
00372
00373 __default__.camera_reset = 0;
00374
00375 __param_descriptions__.push_back(CameraSynchronizerConfig::AbstractParamDescriptionConstPtr(new CameraSynchronizerConfig::ParamDescription<bool>("camera_reset", "bool", 31, "Does a hard reset of all the cameras using a long pulse on the trigger line. This parameter resets itself to false after 3 to 4 seconds.", "", &CameraSynchronizerConfig::camera_reset)));
00376
00377
00378 for (std::vector<CameraSynchronizerConfig::AbstractParamDescriptionConstPtr>::const_iterator i = __param_descriptions__.begin(); i != __param_descriptions__.end(); i++)
00379 __description_message__.parameters.push_back(**i);
00380 __max__.__toMessage__(__description_message__.max, __param_descriptions__);
00381 __min__.__toMessage__(__description_message__.min, __param_descriptions__);
00382 __default__.__toMessage__(__description_message__.dflt, __param_descriptions__);
00383 }
00384 std::vector<CameraSynchronizerConfig::AbstractParamDescriptionConstPtr> __param_descriptions__;
00385 CameraSynchronizerConfig __max__;
00386 CameraSynchronizerConfig __min__;
00387 CameraSynchronizerConfig __default__;
00388 dynamic_reconfigure::ConfigDescription __description_message__;
00389 static const CameraSynchronizerConfigStatics *get_instance()
00390 {
00391
00392
00393
00394
00395 static CameraSynchronizerConfigStatics instance;
00396 return &instance;
00397 }
00398 };
00399
00400 inline const dynamic_reconfigure::ConfigDescription &CameraSynchronizerConfig::__getDescriptionMessage__()
00401 {
00402 return __get_statics__()->__description_message__;
00403 }
00404
00405 inline const CameraSynchronizerConfig &CameraSynchronizerConfig::__getDefault__()
00406 {
00407 return __get_statics__()->__default__;
00408 }
00409
00410 inline const CameraSynchronizerConfig &CameraSynchronizerConfig::__getMax__()
00411 {
00412 return __get_statics__()->__max__;
00413 }
00414
00415 inline const CameraSynchronizerConfig &CameraSynchronizerConfig::__getMin__()
00416 {
00417 return __get_statics__()->__min__;
00418 }
00419
00420 inline const std::vector<CameraSynchronizerConfig::AbstractParamDescriptionConstPtr> &CameraSynchronizerConfig::__getParamDescriptions__()
00421 {
00422 return __get_statics__()->__param_descriptions__;
00423 }
00424
00425 inline const CameraSynchronizerConfigStatics *CameraSynchronizerConfig::__get_statics__()
00426 {
00427 const static CameraSynchronizerConfigStatics *statics;
00428
00429 if (statics)
00430 return statics;
00431
00432 boost::mutex::scoped_lock lock(dynamic_reconfigure::__init_mutex__);
00433
00434 if (statics)
00435 return statics;
00436
00437 statics = CameraSynchronizerConfigStatics::get_instance();
00438
00439 return statics;
00440 }
00441
00442
00443 const int CameraSynchronizer_ProjectorOff = 1;
00444
00445 const int CameraSynchronizer_ProjectorAuto = 2;
00446
00447 const int CameraSynchronizer_ProjectorOn = 3;
00448
00449 const int CameraSynchronizer_InternalTrigger = 1;
00450
00451 const int CameraSynchronizer_IgnoreProjector = 2;
00452
00453 const int CameraSynchronizer_WithProjector = 3;
00454
00455 const int CameraSynchronizer_WithoutProjector = 4;
00456
00457 const int CameraSynchronizer_AlternateProjector = 5;
00458 }
00459
00460 #endif // __CAMERASYNCHRONIZERRECONFIGURATOR_H__