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
00048 #include "ueye_cam/ueye_cam_nodelet.hpp"
00049 #include <cstdlib>
00050 #include <ros/package.h>
00051 #include <camera_calibration_parsers/parse.h>
00052 #include <sensor_msgs/fill_image.h>
00053 #include <sensor_msgs/image_encodings.h>
00054
00055
00056
00057
00058
00059 using namespace std;
00060 using namespace sensor_msgs::image_encodings;
00061
00062
00063 namespace ueye_cam {
00064
00065
00066 const std::string UEyeCamNodelet::DEFAULT_FRAME_NAME = "camera";
00067 const std::string UEyeCamNodelet::DEFAULT_CAMERA_NAME = "camera";
00068 const std::string UEyeCamNodelet::DEFAULT_CAMERA_TOPIC = "image_raw";
00069 const std::string UEyeCamNodelet::DEFAULT_COLOR_MODE = "";
00070 constexpr int UEyeCamDriver::ANY_CAMERA;
00071
00072
00073
00074 UEyeCamNodelet::UEyeCamNodelet() :
00075 nodelet::Nodelet(),
00076 UEyeCamDriver(ANY_CAMERA, DEFAULT_CAMERA_NAME),
00077 frame_grab_alive_(false),
00078 ros_cfg_(NULL),
00079 cfg_sync_requested_(false),
00080 ros_frame_count_(0),
00081 cam_topic_(DEFAULT_CAMERA_TOPIC),
00082 cam_intr_filename_(""),
00083 cam_params_filename_("") {
00084 cam_params_.image_width = DEFAULT_IMAGE_WIDTH;
00085 cam_params_.image_height = DEFAULT_IMAGE_HEIGHT;
00086 cam_params_.image_left = -1;
00087 cam_params_.image_top = -1;
00088 cam_params_.color_mode = DEFAULT_COLOR_MODE;
00089 cam_params_.subsampling = cam_subsampling_rate_;
00090 cam_params_.binning = cam_binning_rate_;
00091 cam_params_.sensor_scaling = cam_sensor_scaling_rate_;
00092 cam_params_.auto_gain = false;
00093 cam_params_.master_gain = 0;
00094 cam_params_.red_gain = 0;
00095 cam_params_.green_gain = 0;
00096 cam_params_.blue_gain = 0;
00097 cam_params_.gain_boost = 0;
00098 cam_params_.auto_exposure = false;
00099 cam_params_.exposure = DEFAULT_EXPOSURE;
00100 cam_params_.auto_white_balance = false;
00101 cam_params_.white_balance_red_offset = 0;
00102 cam_params_.white_balance_blue_offset = 0;
00103 cam_params_.auto_frame_rate = false;
00104 cam_params_.frame_rate = DEFAULT_FRAME_RATE;
00105 cam_params_.pixel_clock = DEFAULT_PIXEL_CLOCK;
00106 cam_params_.ext_trigger_mode = false;
00107 cam_params_.flash_delay = 0;
00108 cam_params_.flash_duration = DEFAULT_FLASH_DURATION;
00109 cam_params_.flip_upd = false;
00110 cam_params_.flip_lr = false;
00111 }
00112
00113
00114 UEyeCamNodelet::~UEyeCamNodelet() {
00115 disconnectCam();
00116
00117
00118
00119
00120
00121
00122
00123
00124 }
00125
00126
00127 void UEyeCamNodelet::onInit() {
00128 ros::NodeHandle& nh = getNodeHandle();
00129 ros::NodeHandle& local_nh = getPrivateNodeHandle();
00130 image_transport::ImageTransport it(nh);
00131
00132
00133 local_nh.param<string>("camera_name", cam_name_, DEFAULT_CAMERA_NAME);
00134 local_nh.param<string>("frame_name", frame_name_, DEFAULT_FRAME_NAME);
00135 local_nh.param<string>("camera_topic", cam_topic_, DEFAULT_CAMERA_TOPIC);
00136 local_nh.param<string>("camera_intrinsics_file", cam_intr_filename_, "");
00137 local_nh.param<int>("camera_id", cam_id_, ANY_CAMERA);
00138 local_nh.param<string>("camera_parameters_file", cam_params_filename_, "");
00139 if (cam_id_ < 0) {
00140 WARN_STREAM("Invalid camera ID specified: " << cam_id_ <<
00141 "; setting to ANY_CAMERA");
00142 cam_id_ = ANY_CAMERA;
00143 }
00144
00145 loadIntrinsicsFile();
00146
00147
00148 ros_cfg_ = new ReconfigureServer(ros_cfg_mutex_, local_nh);
00149 ReconfigureServer::CallbackType f;
00150 f = bind(&UEyeCamNodelet::configCallback, this, _1, _2);
00151
00152
00153 ros_cam_pub_ = it.advertiseCamera(cam_name_ + "/" + cam_topic_, 1);
00154 set_cam_info_srv_ = nh.advertiseService(cam_name_ + "/set_camera_info",
00155 &UEyeCamNodelet::setCamInfo, this);
00156
00157
00158 if (connectCam() != IS_SUCCESS) {
00159 ERROR_STREAM("Failed to initialize [" << cam_name_ << "]");
00160 return;
00161 }
00162 ros_cfg_->setCallback(f);
00163 startFrameGrabber();
00164 INFO_STREAM(
00165 "UEye camera [" << cam_name_ << "] initialized on topic " << ros_cam_pub_.getTopic() << endl <<
00166 "Width:\t\t\t" << cam_params_.image_width << endl <<
00167 "Height:\t\t\t" << cam_params_.image_height << endl <<
00168 "Left Pos.:\t\t" << cam_params_.image_left << endl <<
00169 "Top Pos.:\t\t" << cam_params_.image_top << endl <<
00170 "Color Mode:\t\t" << cam_params_.color_mode << endl <<
00171 "Subsampling:\t\t" << cam_params_.subsampling << endl <<
00172 "Binning:\t\t" << cam_params_.binning << endl <<
00173 "Sensor Scaling:\t\t" << cam_params_.sensor_scaling << endl <<
00174 "Auto Gain:\t\t" << cam_params_.auto_gain << endl <<
00175 "Master Gain:\t\t" << cam_params_.master_gain << endl <<
00176 "Red Gain:\t\t" << cam_params_.red_gain << endl <<
00177 "Green Gain:\t\t" << cam_params_.green_gain << endl <<
00178 "Blue Gain:\t\t" << cam_params_.blue_gain << endl <<
00179 "Gain Boost:\t\t" << cam_params_.gain_boost << endl <<
00180 "Auto Exposure:\t\t" << cam_params_.auto_exposure << endl <<
00181 "Exposure (ms):\t\t" << cam_params_.exposure << endl <<
00182 "Auto White Balance:\t" << cam_params_.auto_white_balance << endl <<
00183 "WB Red Offset:\t\t" << cam_params_.white_balance_red_offset << endl <<
00184 "WB Blue Offset:\t\t" << cam_params_.white_balance_blue_offset << endl <<
00185 "Flash Delay (us):\t" << cam_params_.flash_delay << endl <<
00186 "Flash Duration (us):\t" << cam_params_.flash_duration << endl <<
00187 "Ext Trigger Mode:\t" << cam_params_.ext_trigger_mode << endl <<
00188 "Auto Frame Rate:\t" << cam_params_.auto_frame_rate << endl <<
00189 "Frame Rate (Hz):\t" << cam_params_.frame_rate << endl <<
00190 "Pixel Clock (MHz):\t" << cam_params_.pixel_clock << endl <<
00191 "Mirror Image Upside Down:\t" << cam_params_.flip_upd << endl <<
00192 "Mirror Image Left Right:\t" << cam_params_.flip_lr << endl
00193 );
00194 }
00195
00196
00197 INT UEyeCamNodelet::parseROSParams(ros::NodeHandle& local_nh) {
00198 bool hasNewParams = false;
00199 ueye_cam::UEyeCamConfig prevCamParams = cam_params_;
00200 INT is_err = IS_SUCCESS;
00201
00202 if (local_nh.hasParam("image_width")) {
00203 local_nh.getParam("image_width", cam_params_.image_width);
00204 if (cam_params_.image_width != prevCamParams.image_width) {
00205 if (cam_params_.image_width <= 0) {
00206 WARN_STREAM("Invalid requested image width for [" << cam_name_ <<
00207 "]: " << cam_params_.image_width <<
00208 "; using current width: " << prevCamParams.image_width);
00209 cam_params_.image_width = prevCamParams.image_width;
00210 } else {
00211 hasNewParams = true;
00212 }
00213 }
00214 }
00215 if (local_nh.hasParam("image_height")) {
00216 local_nh.getParam("image_height", cam_params_.image_height);
00217 if (cam_params_.image_height != prevCamParams.image_height) {
00218 if (cam_params_.image_height <= 0) {
00219 WARN_STREAM("Invalid requested image height for [" << cam_name_ <<
00220 "]: " << cam_params_.image_height <<
00221 "; using current height: " << prevCamParams.image_height);
00222 cam_params_.image_height = prevCamParams.image_height;
00223 } else {
00224 hasNewParams = true;
00225 }
00226 }
00227 }
00228 if (local_nh.hasParam("image_top")) {
00229 local_nh.getParam("image_top", cam_params_.image_top);
00230 if (cam_params_.image_top != prevCamParams.image_top) {
00231 hasNewParams = true;
00232 }
00233 }
00234 if (local_nh.hasParam("image_left")) {
00235 local_nh.getParam("image_left", cam_params_.image_left);
00236 if (cam_params_.image_left != prevCamParams.image_left) {
00237 hasNewParams = true;
00238 }
00239 }
00240 if (local_nh.hasParam("color_mode")) {
00241 local_nh.getParam("color_mode", cam_params_.color_mode);
00242 if (cam_params_.color_mode != prevCamParams.color_mode) {
00243 if (cam_params_.color_mode.length() > 0) {
00244 transform(cam_params_.color_mode.begin(),
00245 cam_params_.color_mode.end(),
00246 cam_params_.color_mode.begin(),
00247 ::tolower);
00248 if (cam_params_.color_mode != RGB8 &&
00249 cam_params_.color_mode != BGR8 &&
00250 cam_params_.color_mode != MONO8 &&
00251 cam_params_.color_mode != BAYER_RGGB8) {
00252 WARN_STREAM("Invalid requested color mode for [" << cam_name_ <<
00253 "]: " << cam_params_.color_mode <<
00254 "; using current mode: " << prevCamParams.color_mode);
00255 cam_params_.color_mode = prevCamParams.color_mode;
00256 } else {
00257 hasNewParams = true;
00258 }
00259 } else {
00260 cam_params_.color_mode = prevCamParams.color_mode;
00261 }
00262 }
00263 }
00264 if (local_nh.hasParam("subsampling")) {
00265 local_nh.getParam("subsampling", cam_params_.subsampling);
00266 if (cam_params_.subsampling != prevCamParams.subsampling) {
00267 if (!(cam_params_.subsampling == 1 ||
00268 cam_params_.subsampling == 2 ||
00269 cam_params_.subsampling == 4 ||
00270 cam_params_.subsampling == 8 ||
00271 cam_params_.subsampling == 16)) {
00272 WARN_STREAM("Invalid or unsupported requested subsampling rate for [" <<
00273 cam_name_ << "]: " << cam_params_.subsampling <<
00274 "; using current rate: " << prevCamParams.subsampling);
00275 cam_params_.subsampling = prevCamParams.subsampling;
00276 } else {
00277 hasNewParams = true;
00278 }
00279 }
00280 }
00281 if (local_nh.hasParam("auto_gain")) {
00282 local_nh.getParam("auto_gain", cam_params_.auto_gain);
00283 if (cam_params_.auto_gain != prevCamParams.auto_gain) {
00284 hasNewParams = true;
00285 }
00286 }
00287 if (local_nh.hasParam("master_gain")) {
00288 local_nh.getParam("master_gain", cam_params_.master_gain);
00289 if (cam_params_.master_gain != prevCamParams.master_gain) {
00290 if (cam_params_.master_gain < 0 || cam_params_.master_gain > 100) {
00291 WARN_STREAM("Invalid master gain for [" << cam_name_ << "]: " <<
00292 cam_params_.master_gain << "; using current master gain: " << prevCamParams.master_gain);
00293 cam_params_.master_gain = prevCamParams.master_gain;
00294 } else {
00295 hasNewParams = true;
00296 }
00297 }
00298 }
00299 if (local_nh.hasParam("red_gain")) {
00300 local_nh.getParam("red_gain", cam_params_.red_gain);
00301 if (cam_params_.red_gain != prevCamParams.red_gain) {
00302 if (cam_params_.red_gain < 0 || cam_params_.red_gain > 100) {
00303 WARN_STREAM("Invalid red gain for [" << cam_name_ << "]: " <<
00304 cam_params_.red_gain << "; using current red gain: " << prevCamParams.red_gain);
00305 cam_params_.red_gain = prevCamParams.red_gain;
00306 } else {
00307 hasNewParams = true;
00308 }
00309 }
00310 }
00311 if (local_nh.hasParam("green_gain")) {
00312 local_nh.getParam("green_gain", cam_params_.green_gain);
00313 if (cam_params_.green_gain != prevCamParams.green_gain) {
00314 if (cam_params_.green_gain < 0 || cam_params_.green_gain > 100) {
00315 WARN_STREAM("Invalid green gain for [" << cam_name_ << "]: " <<
00316 cam_params_.green_gain << "; using current green gain: " << prevCamParams.green_gain);
00317 cam_params_.green_gain = prevCamParams.green_gain;
00318 } else {
00319 hasNewParams = true;
00320 }
00321 }
00322 }
00323 if (local_nh.hasParam("blue_gain")) {
00324 local_nh.getParam("blue_gain", cam_params_.blue_gain);
00325 if (cam_params_.blue_gain != prevCamParams.blue_gain) {
00326 if (cam_params_.blue_gain < 0 || cam_params_.blue_gain > 100) {
00327 WARN_STREAM("Invalid blue gain for [" << cam_name_ << "]: " <<
00328 cam_params_.blue_gain << "; using current blue gain: " << prevCamParams.blue_gain);
00329 cam_params_.blue_gain = prevCamParams.blue_gain;
00330 } else {
00331 hasNewParams = true;
00332 }
00333 }
00334 }
00335 if (local_nh.hasParam("gain_boost")) {
00336 local_nh.getParam("gain_boost", cam_params_.gain_boost);
00337 if (cam_params_.gain_boost != prevCamParams.gain_boost) {
00338 hasNewParams = true;
00339 }
00340 }
00341 if (local_nh.hasParam("auto_exposure")) {
00342 local_nh.getParam("auto_exposure", cam_params_.auto_exposure);
00343 if (cam_params_.auto_exposure != prevCamParams.auto_exposure) {
00344 hasNewParams = true;
00345 }
00346 }
00347 if (local_nh.hasParam("exposure")) {
00348 local_nh.getParam("exposure", cam_params_.exposure);
00349 if (cam_params_.exposure != prevCamParams.exposure) {
00350 if (cam_params_.exposure < 0.0) {
00351 WARN_STREAM("Invalid requested exposure: " << cam_params_.exposure <<
00352 "; using current exposure: " << prevCamParams.exposure);
00353 cam_params_.exposure = prevCamParams.exposure;
00354 } else {
00355 hasNewParams = true;
00356 }
00357 }
00358 }
00359 if (local_nh.hasParam("auto_white_balance")) {
00360 local_nh.getParam("auto_white_balance", cam_params_.auto_white_balance);
00361 if (cam_params_.auto_white_balance != prevCamParams.auto_white_balance) {
00362 hasNewParams = true;
00363 }
00364 }
00365 if (local_nh.hasParam("white_balance_red_offset")) {
00366 local_nh.getParam("white_balance_red_offset", cam_params_.white_balance_red_offset);
00367 if (cam_params_.white_balance_red_offset != prevCamParams.white_balance_red_offset) {
00368 if (cam_params_.white_balance_red_offset < -50 || cam_params_.white_balance_red_offset > 50) {
00369 WARN_STREAM("Invalid white balance red offset for [" << cam_name_ << "]: " <<
00370 cam_params_.white_balance_red_offset <<
00371 "; using current white balance red offset: " << prevCamParams.white_balance_red_offset);
00372 cam_params_.white_balance_red_offset = prevCamParams.white_balance_red_offset;
00373 } else {
00374 hasNewParams = true;
00375 }
00376 }
00377 }
00378 if (local_nh.hasParam("white_balance_blue_offset")) {
00379 local_nh.getParam("white_balance_blue_offset", cam_params_.white_balance_blue_offset);
00380 if (cam_params_.white_balance_blue_offset != prevCamParams.white_balance_blue_offset) {
00381 if (cam_params_.white_balance_blue_offset < -50 || cam_params_.white_balance_blue_offset > 50) {
00382 WARN_STREAM("Invalid white balance blue offset for [" << cam_name_ << "]: " <<
00383 cam_params_.white_balance_blue_offset <<
00384 "; using current white balance blue offset: " << prevCamParams.white_balance_blue_offset);
00385 cam_params_.white_balance_blue_offset = prevCamParams.white_balance_blue_offset;
00386 } else {
00387 hasNewParams = true;
00388 }
00389 }
00390 }
00391 if (local_nh.hasParam("ext_trigger_mode")) {
00392 local_nh.getParam("ext_trigger_mode", cam_params_.ext_trigger_mode);
00393
00394
00395
00396 }
00397 if (local_nh.hasParam("flash_delay")) {
00398 local_nh.getParam("flash_delay", cam_params_.flash_delay);
00399
00400
00401
00402 }
00403 if (local_nh.hasParam("flash_duration")) {
00404 local_nh.getParam("flash_duration", cam_params_.flash_duration);
00405 if (cam_params_.flash_duration < 0) {
00406 WARN_STREAM("Invalid flash duration for [" << cam_name_ << "]: " <<
00407 cam_params_.flash_duration <<
00408 "; using current flash duration: " << prevCamParams.flash_duration);
00409 cam_params_.flash_duration = prevCamParams.flash_duration;
00410 }
00411
00412
00413
00414 }
00415 if (local_nh.hasParam("auto_frame_rate")) {
00416 local_nh.getParam("auto_frame_rate", cam_params_.auto_frame_rate);
00417 if (cam_params_.auto_frame_rate != prevCamParams.auto_frame_rate) {
00418 hasNewParams = true;
00419 }
00420 }
00421 if (local_nh.hasParam("frame_rate")) {
00422 local_nh.getParam("frame_rate", cam_params_.frame_rate);
00423 if (cam_params_.frame_rate != prevCamParams.frame_rate) {
00424 if (cam_params_.frame_rate <= 0.0) {
00425 WARN_STREAM("Invalid requested frame rate for [" << cam_name_ << "]: " <<
00426 cam_params_.frame_rate <<
00427 "; using current frame rate: " << prevCamParams.frame_rate);
00428 cam_params_.frame_rate = prevCamParams.frame_rate;
00429 } else {
00430 hasNewParams = true;
00431 }
00432 }
00433 }
00434 if (local_nh.hasParam("pixel_clock")) {
00435 local_nh.getParam("pixel_clock", cam_params_.pixel_clock);
00436 if (cam_params_.pixel_clock != prevCamParams.pixel_clock) {
00437 if (cam_params_.pixel_clock < 0) {
00438 WARN_STREAM("Invalid requested pixel clock for [" << cam_name_ << "]: " <<
00439 cam_params_.pixel_clock <<
00440 "; using current pixel clock: " << prevCamParams.pixel_clock);
00441 cam_params_.pixel_clock = prevCamParams.pixel_clock;
00442 } else {
00443 hasNewParams = true;
00444 }
00445 }
00446 }
00447 if (local_nh.hasParam("flip_upd")) {
00448 local_nh.getParam("flip_upd", cam_params_.flip_upd);
00449 if (cam_params_.flip_upd != prevCamParams.flip_upd) {
00450 hasNewParams = true;
00451 }
00452 }
00453 if (local_nh.hasParam("flip_lr")) {
00454 local_nh.getParam("flip_lr", cam_params_.flip_lr);
00455 if (cam_params_.flip_lr != prevCamParams.flip_lr) {
00456 hasNewParams = true;
00457 }
00458 }
00459
00460 if (hasNewParams) {
00461
00462
00463 if ((is_err = setColorMode(cam_params_.color_mode, false)) != IS_SUCCESS) return is_err;
00464 if ((is_err = setResolution(cam_params_.image_width, cam_params_.image_height,
00465 cam_params_.image_left, cam_params_.image_top, false)) != IS_SUCCESS) return is_err;
00466 if ((is_err = setSubsampling(cam_params_.subsampling, false)) != IS_SUCCESS) return is_err;
00467 if ((is_err = setBinning(cam_params_.binning, false)) != IS_SUCCESS) return is_err;
00468 if ((is_err = setSensorScaling(cam_params_.sensor_scaling, false)) != IS_SUCCESS) return is_err;
00469
00470
00471
00472
00473 if ((is_err = syncCamConfig()) != IS_SUCCESS) return is_err;
00474
00475
00476 if (!cam_params_.auto_exposure) {
00477 cam_params_.auto_frame_rate = false;
00478 }
00479 if (cam_params_.auto_frame_rate) {
00480 cam_params_.auto_gain = false;
00481 }
00482
00483
00484
00485
00486
00487 #define noop (void)0
00488 if ((is_err = setGain(cam_params_.auto_gain, cam_params_.master_gain,
00489 cam_params_.red_gain, cam_params_.green_gain,
00490 cam_params_.blue_gain, cam_params_.gain_boost)) != IS_SUCCESS) noop;
00491 if ((is_err = setPixelClockRate(cam_params_.pixel_clock)) != IS_SUCCESS) return is_err;
00492 if ((is_err = setFrameRate(cam_params_.auto_frame_rate, cam_params_.frame_rate)) != IS_SUCCESS) return is_err;
00493 if ((is_err = setExposure(cam_params_.auto_exposure, cam_params_.exposure)) != IS_SUCCESS) noop;
00494 if ((is_err = setWhiteBalance(cam_params_.auto_white_balance, cam_params_.white_balance_red_offset,
00495 cam_params_.white_balance_blue_offset)) != IS_SUCCESS) noop;
00496 if ((is_err = setMirrorUpsideDown(cam_params_.flip_upd)) != IS_SUCCESS) noop;
00497 if ((is_err = setMirrorLeftRight(cam_params_.flip_lr)) != IS_SUCCESS) noop;
00498 #undef noop
00499 }
00500
00501 DEBUG_STREAM("Successfully applied settings from ROS params to [" << cam_name_ << "]");
00502
00503 return is_err;
00504 }
00505
00506
00507 void UEyeCamNodelet::configCallback(ueye_cam::UEyeCamConfig& config, uint32_t level) {
00508 if (!isConnected()) return;
00509
00510
00511 bool restartFrameGrabber = false;
00512 bool needToReallocateBuffer = false;
00513 if (level == RECONFIGURE_STOP && frame_grab_alive_) {
00514 restartFrameGrabber = true;
00515 stopFrameGrabber();
00516 }
00517
00518
00519 if (config.color_mode != cam_params_.color_mode) {
00520 needToReallocateBuffer = true;
00521 if (setColorMode(config.color_mode, false) != IS_SUCCESS) return;
00522 }
00523
00524 if (config.image_width != cam_params_.image_width ||
00525 config.image_height != cam_params_.image_height ||
00526 config.image_left != cam_params_.image_left ||
00527 config.image_top != cam_params_.image_top) {
00528 needToReallocateBuffer = true;
00529 if (setResolution(config.image_width, config.image_height,
00530 config.image_left, config.image_top, false) != IS_SUCCESS) {
00531
00532 config.image_width = cam_params_.image_width;
00533 config.image_height = cam_params_.image_height;
00534 config.image_left = cam_params_.image_left;
00535 config.image_top = cam_params_.image_top;
00536 if (setResolution(config.image_width, config.image_height,
00537 config.image_left, config.image_top, false) != IS_SUCCESS) return;
00538 }
00539 }
00540
00541 if (config.subsampling != cam_params_.subsampling) {
00542 needToReallocateBuffer = true;
00543 if (setSubsampling(config.subsampling, false) != IS_SUCCESS) return;
00544 }
00545
00546 if (config.binning != cam_params_.binning) {
00547 needToReallocateBuffer = true;
00548 if (setBinning(config.binning, false) != IS_SUCCESS) return;
00549 }
00550
00551 if (config.sensor_scaling != cam_params_.sensor_scaling) {
00552 needToReallocateBuffer = true;
00553 if (setSensorScaling(config.sensor_scaling, false) != IS_SUCCESS) return;
00554 }
00555
00556
00557
00558 if (needToReallocateBuffer) {
00559 if (syncCamConfig() != IS_SUCCESS) return;
00560 needToReallocateBuffer = false;
00561 }
00562
00563
00564 if (!config.auto_exposure) {
00565 config.auto_frame_rate = false;
00566 }
00567 if (config.auto_frame_rate) {
00568 config.auto_gain = false;
00569 }
00570
00571
00572 if (config.auto_gain != cam_params_.auto_gain ||
00573 config.master_gain != cam_params_.master_gain ||
00574 config.red_gain != cam_params_.red_gain ||
00575 config.green_gain != cam_params_.green_gain ||
00576 config.blue_gain != cam_params_.blue_gain ||
00577 config.gain_boost != cam_params_.gain_boost) {
00578
00579 if (config.master_gain != cam_params_.master_gain ||
00580 config.red_gain != cam_params_.red_gain ||
00581 config.green_gain != cam_params_.green_gain ||
00582 config.blue_gain != cam_params_.blue_gain ||
00583 config.gain_boost != cam_params_.gain_boost) {
00584 config.auto_gain = false;
00585 }
00586
00587 if (setGain(config.auto_gain, config.master_gain,
00588 config.red_gain, config.green_gain,
00589 config.blue_gain, config.gain_boost) != IS_SUCCESS) return;
00590 }
00591
00592 if (config.pixel_clock != cam_params_.pixel_clock) {
00593 if (setPixelClockRate(config.pixel_clock) != IS_SUCCESS) return;
00594 }
00595
00596 if (config.auto_frame_rate != cam_params_.auto_frame_rate ||
00597 config.frame_rate != cam_params_.frame_rate) {
00598 if (setFrameRate(config.auto_frame_rate, config.frame_rate) != IS_SUCCESS) return;
00599 }
00600
00601 if (config.auto_exposure != cam_params_.auto_exposure ||
00602 config.exposure != cam_params_.exposure) {
00603 if (setExposure(config.auto_exposure, config.exposure) != IS_SUCCESS) return;
00604 }
00605
00606 if (config.auto_white_balance != cam_params_.auto_white_balance ||
00607 config.white_balance_red_offset != cam_params_.white_balance_red_offset ||
00608 config.white_balance_blue_offset != cam_params_.white_balance_blue_offset) {
00609 if (setWhiteBalance(config.auto_white_balance, config.white_balance_red_offset,
00610 config.white_balance_blue_offset) != IS_SUCCESS) return;
00611 }
00612
00613 if (config.flip_upd != cam_params_.flip_upd) {
00614 if (setMirrorUpsideDown(config.flip_upd) != IS_SUCCESS) return;
00615 }
00616 if (config.flip_lr != cam_params_.flip_lr) {
00617 if (setMirrorLeftRight(config.flip_lr) != IS_SUCCESS) return;
00618 }
00619
00620
00621
00622 if (config.flash_delay != cam_params_.flash_delay ||
00623 config.flash_duration != cam_params_.flash_duration) {
00624
00625
00626
00627 INT flash_delay = config.flash_delay;
00628 UINT flash_duration = config.flash_duration;
00629 if (setFlashParams(flash_delay, flash_duration) != IS_SUCCESS) return;
00630
00631 config.flash_delay = flash_delay;
00632 config.flash_duration = flash_duration;
00633 }
00634
00635
00636 cam_params_ = config;
00637
00638
00639 cfg_sync_requested_ = true;
00640 if (restartFrameGrabber) {
00641 startFrameGrabber();
00642 }
00643
00644 DEBUG_STREAM("Successfully applied settings from dyncfg to [" << cam_name_ << "]");
00645 }
00646
00647
00648 INT UEyeCamNodelet::syncCamConfig(string dft_mode_str) {
00649 INT is_err;
00650
00651 if ((is_err = UEyeCamDriver::syncCamConfig(dft_mode_str)) != IS_SUCCESS) return is_err;
00652
00653
00654 INT query = is_SetColorMode(cam_handle_, IS_GET_COLOR_MODE);
00655 if (query == IS_CM_MONO8) cam_params_.color_mode = MONO8;
00656 else if (query == IS_CM_SENSOR_RAW8) cam_params_.color_mode = BAYER_RGGB8;
00657 else if (query == IS_CM_RGB8_PACKED) cam_params_.color_mode = RGB8;
00658 else if (query == IS_CM_BGR8_PACKED) cam_params_.color_mode = BGR8;
00659 else {
00660 ERROR_STREAM("Force-updating to default color mode for [" << cam_name_ << "]: " <<
00661 dft_mode_str << "\n(THIS IS A CODING ERROR, PLEASE CONTACT PACKAGE AUTHOR)");
00662 cam_params_.color_mode = dft_mode_str;
00663 setColorMode(cam_params_.color_mode);
00664 }
00665
00666
00667 cam_params_.image_width = cam_aoi_.s32Width;
00668 cam_params_.image_height = cam_aoi_.s32Height;
00669 if (cam_params_.image_left >= 0) cam_params_.image_left = cam_aoi_.s32X;
00670 if (cam_params_.image_top >= 0) cam_params_.image_top = cam_aoi_.s32Y;
00671 cam_params_.subsampling = cam_subsampling_rate_;
00672 cam_params_.binning = cam_binning_rate_;
00673 cam_params_.sensor_scaling = cam_sensor_scaling_rate_;
00674
00675
00676
00677 ros_image_.header.frame_id = "/" + frame_name_;
00678 ros_image_.height = cam_params_.image_height / (cam_params_.sensor_scaling * cam_params_.subsampling * cam_params_.binning);
00679 ros_image_.width = cam_params_.image_width / (cam_params_.sensor_scaling * cam_params_.subsampling * cam_params_.binning);
00680 ros_image_.encoding = cam_params_.color_mode;
00681 ros_image_.step = cam_buffer_pitch_;
00682 ros_image_.is_bigendian = 0;
00683 ros_image_.data.resize(cam_buffer_size_);
00684
00685 DEBUG_STREAM("(Re-)allocated ROS image buffer for [" << cam_name_ << "]:" <<
00686 "\n size: " << cam_buffer_size_ <<
00687 "\n width: " << ros_image_.width <<
00688 "\n height: " << ros_image_.height <<
00689 "\n step: " << ros_image_.step <<
00690 "\n encoding: " << ros_image_.encoding);
00691
00692 return is_err;
00693 }
00694
00695
00696 INT UEyeCamNodelet::queryCamParams() {
00697 INT is_err = IS_SUCCESS;
00698 INT query;
00699 double pval1, pval2;
00700
00701
00702
00703
00704
00705 if ((is_err = is_SetAutoParameter(cam_handle_,
00706 IS_GET_ENABLE_AUTO_SENSOR_GAIN, &pval1, &pval2)) != IS_SUCCESS &&
00707 (is_err = is_SetAutoParameter(cam_handle_,
00708 IS_GET_ENABLE_AUTO_GAIN, &pval1, &pval2)) != IS_SUCCESS) {
00709 ERROR_STREAM("Failed to query auto gain mode for UEye camera '" <<
00710 cam_name_ << "' (" << err2str(is_err) << ")");
00711 return is_err;
00712 }
00713 cam_params_.auto_gain = (pval1 != 0);
00714
00715 cam_params_.master_gain = is_SetHardwareGain(cam_handle_, IS_GET_MASTER_GAIN,
00716 IS_IGNORE_PARAMETER, IS_IGNORE_PARAMETER, IS_IGNORE_PARAMETER);
00717 cam_params_.red_gain = is_SetHardwareGain(cam_handle_, IS_GET_RED_GAIN,
00718 IS_IGNORE_PARAMETER, IS_IGNORE_PARAMETER, IS_IGNORE_PARAMETER);
00719 cam_params_.green_gain = is_SetHardwareGain(cam_handle_, IS_GET_GREEN_GAIN,
00720 IS_IGNORE_PARAMETER, IS_IGNORE_PARAMETER, IS_IGNORE_PARAMETER);
00721 cam_params_.blue_gain = is_SetHardwareGain(cam_handle_, IS_GET_BLUE_GAIN,
00722 IS_IGNORE_PARAMETER, IS_IGNORE_PARAMETER, IS_IGNORE_PARAMETER);
00723
00724 query = is_SetGainBoost(cam_handle_, IS_GET_SUPPORTED_GAINBOOST);
00725 if(query == IS_SET_GAINBOOST_ON) {
00726 query = is_SetGainBoost(cam_handle_, IS_GET_GAINBOOST);
00727 if (query == IS_SET_GAINBOOST_ON) {
00728 cam_params_.gain_boost = true;
00729 } else if (query == IS_SET_GAINBOOST_OFF) {
00730 cam_params_.gain_boost = false;
00731 } else {
00732 ERROR_STREAM("Failed to query gain boost for [" << cam_name_ <<
00733 "] (" << err2str(query) << ")");
00734 return query;
00735 }
00736 } else {
00737 cam_params_.gain_boost = false;
00738 }
00739
00740 if ((is_err = is_SetAutoParameter(cam_handle_,
00741 IS_GET_ENABLE_AUTO_SENSOR_SHUTTER, &pval1, &pval2)) != IS_SUCCESS &&
00742 (is_err = is_SetAutoParameter(cam_handle_,
00743 IS_GET_ENABLE_AUTO_SHUTTER, &pval1, &pval2)) != IS_SUCCESS) {
00744 ERROR_STREAM("Failed to query auto shutter mode for [" << cam_name_ <<
00745 "] (" << err2str(is_err) << ")");
00746 return is_err;
00747 }
00748 cam_params_.auto_exposure = (pval1 != 0);
00749
00750 if ((is_err = is_Exposure(cam_handle_, IS_EXPOSURE_CMD_GET_EXPOSURE,
00751 &cam_params_.exposure, sizeof(cam_params_.exposure))) != IS_SUCCESS) {
00752 ERROR_STREAM("Failed to query exposure timing for [" << cam_name_ <<
00753 "] (" << err2str(is_err) << ")");
00754 return is_err;
00755 }
00756
00757 if ((is_err = is_SetAutoParameter(cam_handle_,
00758 IS_GET_ENABLE_AUTO_SENSOR_WHITEBALANCE, &pval1, &pval2)) != IS_SUCCESS &&
00759 (is_err = is_SetAutoParameter(cam_handle_,
00760 IS_GET_ENABLE_AUTO_WHITEBALANCE, &pval1, &pval2)) != IS_SUCCESS) {
00761 ERROR_STREAM("Failed to query auto white balance mode for [" << cam_name_ <<
00762 "] (" << err2str(is_err) << ")");
00763 return is_err;
00764 }
00765 cam_params_.auto_white_balance = (pval1 != 0);
00766
00767 if ((is_err = is_SetAutoParameter(cam_handle_,
00768 IS_GET_AUTO_WB_OFFSET, &pval1, &pval2)) != IS_SUCCESS) {
00769 ERROR_STREAM("Failed to query auto white balance red/blue channel offsets for [" <<
00770 cam_name_ << "] (" << err2str(is_err) << ")");
00771 return is_err;
00772 }
00773 cam_params_.white_balance_red_offset = pval1;
00774 cam_params_.white_balance_blue_offset = pval2;
00775
00776 IO_FLASH_PARAMS currFlashParams;
00777 if ((is_err = is_IO(cam_handle_, IS_IO_CMD_FLASH_GET_PARAMS,
00778 (void*) &currFlashParams, sizeof(IO_FLASH_PARAMS))) != IS_SUCCESS) {
00779 ERROR_STREAM("Could not retrieve current flash parameter info for [" <<
00780 cam_name_ << "] (" << err2str(is_err) << ")");
00781 return is_err;
00782 }
00783 cam_params_.flash_delay = currFlashParams.s32Delay;
00784 cam_params_.flash_duration = currFlashParams.u32Duration;
00785
00786 if ((is_err = is_SetAutoParameter(cam_handle_,
00787 IS_GET_ENABLE_AUTO_SENSOR_FRAMERATE, &pval1, &pval2)) != IS_SUCCESS &&
00788 (is_err = is_SetAutoParameter(cam_handle_,
00789 IS_GET_ENABLE_AUTO_FRAMERATE, &pval1, &pval2)) != IS_SUCCESS) {
00790 ERROR_STREAM("Failed to query auto frame rate mode for [" << cam_name_ <<
00791 "] (" << err2str(is_err) << ")");
00792 return is_err;
00793 }
00794 cam_params_.auto_frame_rate = (pval1 != 0);
00795
00796 if ((is_err = is_SetFrameRate(cam_handle_, IS_GET_FRAMERATE, &cam_params_.frame_rate)) != IS_SUCCESS) {
00797 ERROR_STREAM("Failed to query frame rate for [" << cam_name_ <<
00798 "] (" << err2str(is_err) << ")");
00799 return is_err;
00800 }
00801
00802 UINT currPixelClock;
00803 if ((is_err = is_PixelClock(cam_handle_, IS_PIXELCLOCK_CMD_GET,
00804 (void*) &currPixelClock, sizeof(currPixelClock))) != IS_SUCCESS) {
00805 ERROR_STREAM("Failed to query pixel clock rate for [" << cam_name_ <<
00806 "] (" << err2str(is_err) << ")");
00807 return is_err;
00808 }
00809 cam_params_.pixel_clock = currPixelClock;
00810
00811 INT currROP = is_SetRopEffect(cam_handle_, IS_GET_ROP_EFFECT, 0, 0);
00812 cam_params_.flip_upd = ((currROP & IS_SET_ROP_MIRROR_UPDOWN) == IS_SET_ROP_MIRROR_UPDOWN);
00813 cam_params_.flip_lr = ((currROP & IS_SET_ROP_MIRROR_LEFTRIGHT) == IS_SET_ROP_MIRROR_LEFTRIGHT);
00814
00815
00816
00817
00818 DEBUG_STREAM("Successfully queries parameters from [" << cam_name_ << "]");
00819
00820 return is_err;
00821 }
00822
00823
00824 INT UEyeCamNodelet::connectCam() {
00825 INT is_err = IS_SUCCESS;
00826
00827 if ((is_err = UEyeCamDriver::connectCam()) != IS_SUCCESS) return is_err;
00828
00829
00830 if (cam_params_filename_.length() <= 0) {
00831 cam_params_filename_ = string(getenv("HOME")) + "/.ros/camera_conf/" + cam_name_ + ".ini";
00832 }
00833 if ((is_err = loadCamConfig(cam_params_filename_)) != IS_SUCCESS) return is_err;
00834
00835
00836 if ((is_err = queryCamParams()) != IS_SUCCESS) return is_err;
00837
00838
00839 if ((is_err = parseROSParams(getPrivateNodeHandle())) != IS_SUCCESS) return is_err;
00840
00841 return IS_SUCCESS;
00842 }
00843
00844
00845 INT UEyeCamNodelet::disconnectCam() {
00846 INT is_err = IS_SUCCESS;
00847
00848 if (isConnected()) {
00849 stopFrameGrabber();
00850 is_err = UEyeCamDriver::disconnectCam();
00851 }
00852
00853 return is_err;
00854 }
00855
00856
00857 bool UEyeCamNodelet::setCamInfo(sensor_msgs::SetCameraInfo::Request& req,
00858 sensor_msgs::SetCameraInfo::Response& rsp) {
00859 ros_cam_info_ = req.camera_info;
00860 ros_cam_info_.header.frame_id = "/" + frame_name_;
00861 rsp.success = saveIntrinsicsFile();
00862 rsp.status_message = (rsp.success) ?
00863 "successfully wrote camera info to file" :
00864 "failed to write camera info to file";
00865 return true;
00866 }
00867
00868
00869 void UEyeCamNodelet::frameGrabLoop() {
00870 #ifdef DEBUG_PRINTOUT_FRAME_GRAB_RATES
00871 ros::Time prevStartGrab = ros::Time::now();
00872 ros::Time prevGrabbedFrame = ros::Time::now();
00873 ros::Time currStartGrab;
00874 ros::Time currGrabbedFrame;
00875 double startGrabSum = 0;
00876 double grabbedFrameSum = 0;
00877 double startGrabSumSqrd = 0;
00878 double grabbedFrameSumSqrd = 0;
00879 unsigned int startGrabCount = 0;
00880 unsigned int grabbedFrameCount = 0;
00881 #endif
00882
00883 DEBUG_STREAM("Starting threaded frame grabber loop for [" << cam_name_ << "]");
00884
00885 ros::Rate idleDelay(200);
00886
00887 int prevNumSubscribers = 0;
00888 int currNumSubscribers = 0;
00889 while (frame_grab_alive_ && ros::ok()) {
00890
00891
00892 currNumSubscribers = ros_cam_pub_.getNumSubscribers();
00893 if (currNumSubscribers > 0 && prevNumSubscribers <= 0) {
00894 if (cam_params_.ext_trigger_mode) {
00895 if (setExtTriggerMode() != IS_SUCCESS) {
00896 ERROR_STREAM("Shutting down driver nodelet for [" << cam_name_ << "]");
00897 ros::shutdown();
00898 return;
00899 }
00900 INFO_STREAM("[" << cam_name_ << "] set to external trigger mode");
00901 } else {
00902
00903
00904
00905 INT flash_delay = cam_params_.flash_delay;
00906 UINT flash_duration = cam_params_.flash_duration;
00907 if ((setFreeRunMode() != IS_SUCCESS) ||
00908 (setFlashParams(flash_delay, flash_duration) != IS_SUCCESS)) {
00909 ERROR_STREAM("Shutting down driver nodelet for [" << cam_name_ << "]");
00910 ros::shutdown();
00911 return;
00912 }
00913
00914 cam_params_.flash_delay = flash_delay;
00915 cam_params_.flash_duration = flash_duration;
00916 INFO_STREAM("[" << cam_name_ << "] set to free-run mode");
00917 }
00918 } else if (currNumSubscribers <= 0 && prevNumSubscribers > 0) {
00919 if (setStandbyMode() != IS_SUCCESS) {
00920 ERROR_STREAM("Shutting down driver nodelet for [" << cam_name_ << "]");
00921 ros::shutdown();
00922 return;
00923 }
00924 INFO_STREAM("[" << cam_name_ << "] set to standby mode");
00925 }
00926 prevNumSubscribers = currNumSubscribers;
00927
00928
00929 if (cfg_sync_requested_) {
00930 if (ros_cfg_mutex_.try_lock()) {
00931 ros_cfg_mutex_.unlock();
00932 ros_cfg_->updateConfig(cam_params_);
00933 cfg_sync_requested_ = false;
00934 }
00935 }
00936
00937
00938 #ifdef DEBUG_PRINTOUT_FRAME_GRAB_RATES
00939 startGrabCount++;
00940 currStartGrab = ros::Time::now();
00941 if (startGrabCount > 1) {
00942 startGrabSum += (currStartGrab - prevStartGrab).toSec() * 1000.0;
00943 startGrabSumSqrd += ((currStartGrab - prevStartGrab).toSec() * 1000.0)*((currStartGrab - prevStartGrab).toSec() * 1000.0);
00944 }
00945 prevStartGrab = currStartGrab;
00946 #endif
00947
00948 if (isCapturing()) {
00949 INT eventTimeout = (cam_params_.auto_frame_rate || cam_params_.ext_trigger_mode) ?
00950 (INT) 2000 : (INT) (1000.0 / cam_params_.frame_rate * 2);
00951 if (processNextFrame(eventTimeout) != NULL) {
00952 ros_image_.header.stamp = ros_cam_info_.header.stamp = getImageTimestamp();
00953
00954 #ifdef DEBUG_PRINTOUT_FRAME_GRAB_RATES
00955 grabbedFrameCount++;
00956 currGrabbedFrame = ros::Time::now();
00957 if (grabbedFrameCount > 1) {
00958 grabbedFrameSum += (currGrabbedFrame - prevGrabbedFrame).toSec() * 1000.0;
00959 grabbedFrameSumSqrd += ((currGrabbedFrame - prevGrabbedFrame).toSec() * 1000.0)*((currGrabbedFrame - prevGrabbedFrame).toSec() * 1000.0);
00960 }
00961 prevGrabbedFrame = currGrabbedFrame;
00962
00963 if (grabbedFrameCount > 1) {
00964 WARN_STREAM("\nPre-Grab: " << startGrabSum/startGrabCount << " +/- " <<
00965 sqrt(startGrabSumSqrd/startGrabCount - (startGrabSum/startGrabCount)*(startGrabSum/startGrabCount)) << " ms (" <<
00966 1000.0*startGrabCount/startGrabSum << "Hz)\n" <<
00967 "Post-Grab: " << grabbedFrameSum/grabbedFrameCount << " +/- " <<
00968 sqrt(grabbedFrameSumSqrd/grabbedFrameCount - (grabbedFrameSum/grabbedFrameCount)*(grabbedFrameSum/grabbedFrameCount)) << " ms (" <<
00969 1000.0*grabbedFrameCount/grabbedFrameSum << "Hz)\n" <<
00970 "Target: " << cam_params_.frame_rate << "Hz");
00971 }
00972 #endif
00973
00974 if (!frame_grab_alive_ || !ros::ok()) break;
00975
00976 ros_cam_info_.width = cam_params_.image_width / cam_sensor_scaling_rate_ / cam_subsampling_rate_ / cam_binning_rate_;
00977 ros_cam_info_.height = cam_params_.image_height / cam_sensor_scaling_rate_ / cam_subsampling_rate_ / cam_binning_rate_;
00978
00979
00980
00981 int expected_row_stride = ros_cam_info_.width * bits_per_pixel_ / 8;
00982 if (cam_buffer_pitch_ < expected_row_stride) {
00983 ERROR_STREAM("Camera buffer pitch (" << cam_buffer_pitch_ <<
00984 ") is smaller than expected for [" << cam_name_ << "]: " <<
00985 "width (" << ros_cam_info_.width << ") * bytes per pixel (" <<
00986 bits_per_pixel_/8 << ") = " << expected_row_stride);
00987 continue;
00988 } else if (cam_buffer_pitch_ == expected_row_stride) {
00989
00990 copy((char*) cam_buffer_,
00991 ((char*) cam_buffer_) + cam_buffer_size_,
00992 ros_image_.data.begin());
00993 } else {
00994
00995 std::vector<unsigned char>::iterator ros_image_it = ros_image_.data.begin();
00996 char* cam_buffer_ptr = cam_buffer_;
00997 for (unsigned int row = 0; row < ros_cam_info_.height; row++) {
00998 ros_image_it = copy(cam_buffer_ptr, cam_buffer_ptr + expected_row_stride, ros_image_it);
00999 cam_buffer_ptr += expected_row_stride;
01000 }
01001 ros_image_.step = expected_row_stride;
01002 }
01003 ros_image_.header.seq = ros_cam_info_.header.seq = ros_frame_count_++;
01004 ros_image_.header.frame_id = ros_cam_info_.header.frame_id;
01005
01006 if (!frame_grab_alive_ || !ros::ok()) break;
01007 ros_cam_pub_.publish(ros_image_, ros_cam_info_);
01008 }
01009 }
01010
01011 if (!frame_grab_alive_ || !ros::ok()) break;
01012 idleDelay.sleep();
01013 }
01014
01015 setStandbyMode();
01016 frame_grab_alive_ = false;
01017
01018 DEBUG_STREAM("Frame grabber loop terminated for [" << cam_name_ << "]");
01019 }
01020
01021
01022 void UEyeCamNodelet::startFrameGrabber() {
01023 frame_grab_alive_ = true;
01024 frame_grab_thread_ = thread(bind(&UEyeCamNodelet::frameGrabLoop, this));
01025 }
01026
01027
01028 void UEyeCamNodelet::stopFrameGrabber() {
01029 frame_grab_alive_ = false;
01030 if (frame_grab_thread_.joinable()) {
01031 frame_grab_thread_.join();
01032 }
01033 frame_grab_thread_ = thread();
01034 }
01035
01036
01037 void UEyeCamNodelet::loadIntrinsicsFile() {
01038 if (cam_intr_filename_.length() <= 0) {
01039 cam_intr_filename_ = string(getenv("HOME")) + "/.ros/camera_info/" + cam_name_ + ".yaml";
01040 }
01041
01042 if (camera_calibration_parsers::readCalibration(cam_intr_filename_, cam_name_, ros_cam_info_)) {
01043 DEBUG_STREAM("Loaded intrinsics parameters for [" << cam_name_ << "]");
01044 }
01045 ros_cam_info_.header.frame_id = "/" + frame_name_;
01046 }
01047
01048
01049 bool UEyeCamNodelet::saveIntrinsicsFile() {
01050 if (camera_calibration_parsers::writeCalibration(cam_intr_filename_, cam_name_, ros_cam_info_)) {
01051 DEBUG_STREAM("Saved intrinsics parameters for [" << cam_name_ <<
01052 "] to " << cam_intr_filename_);
01053 return true;
01054 }
01055 return false;
01056 }
01057
01058 ros::Time UEyeCamNodelet::getImageTimestamp() {
01059 UEYETIME utime;
01060 if(getTimestamp(&utime)) {
01061 struct tm tm;
01062 tm.tm_year = utime.wYear - 1900;
01063 tm.tm_mon = utime.wMonth - 1;
01064 tm.tm_mday = utime.wDay;
01065 tm.tm_hour = utime.wHour;
01066 tm.tm_min = utime.wMinute;
01067 tm.tm_sec = utime.wSecond;
01068 return ros::Time(mktime(&tm),utime.wMilliseconds*1e6);
01069 }
01070 return ros::Time::now();
01071 }
01072
01073
01074 }
01075
01076
01077
01078
01079
01080 #include <pluginlib/class_list_macros.h>
01081 PLUGINLIB_EXPORT_CLASS(ueye_cam::UEyeCamNodelet, nodelet::Nodelet)