52 #include <std_msgs/UInt64.h> 67 const std::string UEyeCamNodelet::DEFAULT_FRAME_NAME =
"camera";
68 const std::string UEyeCamNodelet::DEFAULT_CAMERA_NAME =
"camera";
69 const std::string UEyeCamNodelet::DEFAULT_CAMERA_TOPIC =
"image_raw";
70 const std::string UEyeCamNodelet::DEFAULT_TIMEOUT_TOPIC =
"timeout_count";
71 const std::string UEyeCamNodelet::DEFAULT_COLOR_MODE =
"";
72 constexpr
int UEyeCamDriver::ANY_CAMERA;
76 UEyeCamNodelet::UEyeCamNodelet():
79 frame_grab_alive_(false),
81 cfg_sync_requested_(false),
84 cam_topic_(DEFAULT_CAMERA_TOPIC),
85 timeout_topic_(DEFAULT_TIMEOUT_TOPIC),
86 cam_intr_filename_(
""),
87 cam_params_filename_(
""),
89 init_publish_time_(0),
90 prev_output_frame_idx_(0) {
91 ros_image_.is_bigendian = (__BYTE_ORDER__ == __ORDER_BIG_ENDIAN__);
156 WARN_STREAM(
"Invalid camera ID specified: " << cam_id_ <<
157 "; setting to ANY_CAMERA");
172 ERROR_STREAM(
"Failed to initialize [" << cam_name_ <<
"]");
178 ReconfigureServer::CallbackType
f;
184 "Width:\t\t\t" <<
cam_params_.image_width << endl <<
185 "Height:\t\t\t" <<
cam_params_.image_height << endl <<
186 "Left Pos.:\t\t" <<
cam_params_.image_left << endl <<
187 "Top Pos.:\t\t" <<
cam_params_.image_top << endl <<
188 "Color Mode:\t\t" <<
cam_params_.color_mode << endl <<
189 "Subsampling:\t\t" <<
cam_params_.subsampling << endl <<
191 "Sensor Scaling:\t\t" <<
cam_params_.sensor_scaling << endl <<
192 "Auto Gain:\t\t" <<
cam_params_.auto_gain << endl <<
193 "Master Gain:\t\t" <<
cam_params_.master_gain << endl <<
195 "Green Gain:\t\t" <<
cam_params_.green_gain << endl <<
196 "Blue Gain:\t\t" <<
cam_params_.blue_gain << endl <<
197 "Gain Boost:\t\t" <<
cam_params_.gain_boost << endl <<
198 "Software Gamma:\t\t" <<
cam_params_.software_gamma << endl <<
199 "Auto Exposure:\t\t" <<
cam_params_.auto_exposure << endl <<
200 "Auto Exposure Reference:\t" <<
cam_params_.auto_exposure_reference << endl <<
201 "Exposure (ms):\t\t" <<
cam_params_.exposure << endl <<
202 "Auto White Balance:\t" <<
cam_params_.auto_white_balance << endl <<
203 "WB Red Offset:\t\t" <<
cam_params_.white_balance_red_offset << endl <<
204 "WB Blue Offset:\t\t" <<
cam_params_.white_balance_blue_offset << endl <<
205 "Flash Delay (us):\t" <<
cam_params_.flash_delay << endl <<
206 "Flash Duration (us):\t" <<
cam_params_.flash_duration << endl <<
207 "Ext Trigger Mode:\t" <<
cam_params_.ext_trigger_mode << endl <<
208 "Auto Frame Rate:\t" <<
cam_params_.auto_frame_rate << endl <<
209 "Frame Rate (Hz):\t" <<
cam_params_.frame_rate << endl <<
210 "Output Rate (Hz):\t" <<
cam_params_.output_rate << endl <<
211 "Pixel Clock (MHz):\t" <<
cam_params_.pixel_clock << endl <<
214 "Mirror Image Upside Down:\t" <<
cam_params_.flip_upd << endl <<
215 "Mirror Image Left Right:\t" <<
cam_params_.flip_lr << endl
221 bool hasNewParams =
false;
222 ueye_cam::UEyeCamConfig prevCamParams =
cam_params_;
223 INT is_err = IS_SUCCESS;
225 if (local_nh.
hasParam(
"image_width")) {
227 if (
cam_params_.image_width != prevCamParams.image_width) {
231 "; using current width: " << prevCamParams.image_width);
232 cam_params_.image_width = prevCamParams.image_width;
240 if (local_nh.
hasParam(
"image_height")) {
242 if (
cam_params_.image_height != prevCamParams.image_height) {
246 "; using current height: " << prevCamParams.image_height);
247 cam_params_.image_height = prevCamParams.image_height;
255 if (local_nh.
hasParam(
"image_top")) {
257 if (
cam_params_.image_top != prevCamParams.image_top) {
263 if (local_nh.
hasParam(
"image_left")) {
265 if (
cam_params_.image_left != prevCamParams.image_left) {
271 if (local_nh.
hasParam(
"color_mode")) {
273 if (
cam_params_.color_mode != prevCamParams.color_mode) {
284 <<
"; using current mode: " << prevCamParams.color_mode);
294 if (local_nh.
hasParam(
"subsampling")) {
296 if (
cam_params_.subsampling != prevCamParams.subsampling) {
302 WARN_STREAM(
"Invalid or unsupported requested subsampling rate for [" <<
304 "; using current rate: " << prevCamParams.subsampling);
305 cam_params_.subsampling = prevCamParams.subsampling;
313 if (local_nh.
hasParam(
"auto_gain")) {
315 if (
cam_params_.auto_gain != prevCamParams.auto_gain) {
321 if (local_nh.
hasParam(
"master_gain")) {
323 if (
cam_params_.master_gain != prevCamParams.master_gain) {
326 cam_params_.master_gain <<
"; using current master gain: " << prevCamParams.master_gain);
327 cam_params_.master_gain = prevCamParams.master_gain;
335 if (local_nh.
hasParam(
"red_gain")) {
337 if (
cam_params_.red_gain != prevCamParams.red_gain) {
340 cam_params_.red_gain <<
"; using current red gain: " << prevCamParams.red_gain);
349 if (local_nh.
hasParam(
"green_gain")) {
351 if (
cam_params_.green_gain != prevCamParams.green_gain) {
354 cam_params_.green_gain <<
"; using current green gain: " << prevCamParams.green_gain);
363 if (local_nh.
hasParam(
"blue_gain")) {
365 if (
cam_params_.blue_gain != prevCamParams.blue_gain) {
368 cam_params_.blue_gain <<
"; using current blue gain: " << prevCamParams.blue_gain);
377 if (local_nh.
hasParam(
"gain_boost")) {
379 if (
cam_params_.gain_boost != prevCamParams.gain_boost) {
385 if (local_nh.
hasParam(
"software_gamma")) {
387 if (
cam_params_.software_gamma != prevCamParams.software_gamma) {
391 if (local_nh.
hasParam(
"auto_exposure")) {
393 if (
cam_params_.auto_exposure != prevCamParams.auto_exposure) {
399 if (local_nh.
hasParam(
"auto_exposure_reference")) {
401 if (
cam_params_.auto_exposure_reference != prevCamParams.auto_exposure_reference) {
407 if (local_nh.
hasParam(
"exposure")) {
409 if (
cam_params_.exposure != prevCamParams.exposure) {
412 "; using current exposure: " << prevCamParams.exposure);
421 if (local_nh.
hasParam(
"auto_white_balance")) {
423 if (
cam_params_.auto_white_balance != prevCamParams.auto_white_balance) {
429 if (local_nh.
hasParam(
"white_balance_red_offset")) {
431 if (
cam_params_.white_balance_red_offset != prevCamParams.white_balance_red_offset) {
435 "; using current white balance red offset: " << prevCamParams.white_balance_red_offset);
436 cam_params_.white_balance_red_offset = prevCamParams.white_balance_red_offset;
444 if (local_nh.
hasParam(
"white_balance_blue_offset")) {
446 if (
cam_params_.white_balance_blue_offset != prevCamParams.white_balance_blue_offset) {
450 "; using current white balance blue offset: " << prevCamParams.white_balance_blue_offset);
451 cam_params_.white_balance_blue_offset = prevCamParams.white_balance_blue_offset;
459 if (local_nh.
hasParam(
"ext_trigger_mode")) {
467 if (local_nh.
hasParam(
"flash_delay")) {
475 if (local_nh.
hasParam(
"flash_duration")) {
480 "; using current flash duration: " << prevCamParams.flash_duration);
481 cam_params_.flash_duration = prevCamParams.flash_duration;
491 if (
cam_params_.gpio1 != prevCamParams.gpio1) {hasNewParams =
true;}
497 if (
cam_params_.gpio2 != prevCamParams.gpio2) {hasNewParams =
true;}
501 if (local_nh.
hasParam(
"pwm_freq")) {
503 if (
cam_params_.pwm_freq != prevCamParams.pwm_freq) {hasNewParams =
true;}
507 if (local_nh.
hasParam(
"pwm_duty_cycle")) {
509 if (
cam_params_.pwm_duty_cycle != prevCamParams.pwm_duty_cycle) {hasNewParams =
true;}
514 if (local_nh.
hasParam(
"auto_frame_rate")) {
516 if (
cam_params_.auto_frame_rate != prevCamParams.auto_frame_rate) {
522 if (local_nh.
hasParam(
"frame_rate")) {
524 if (
cam_params_.frame_rate != prevCamParams.frame_rate) {
528 "; using current frame rate: " << prevCamParams.frame_rate);
537 if (local_nh.
hasParam(
"output_rate")) {
542 "; disable publisher throttling by default");
551 if (local_nh.
hasParam(
"pixel_clock")) {
553 if (
cam_params_.pixel_clock != prevCamParams.pixel_clock) {
557 "; using current pixel clock: " << prevCamParams.pixel_clock);
558 cam_params_.pixel_clock = prevCamParams.pixel_clock;
566 if (local_nh.
hasParam(
"flip_upd")) {
568 if (
cam_params_.flip_upd != prevCamParams.flip_upd) {
576 if (
cam_params_.flip_lr != prevCamParams.flip_lr) {
637 bool restartFrameGrabber =
false;
638 bool needToReallocateBuffer =
false;
640 restartFrameGrabber =
true;
646 needToReallocateBuffer =
true;
647 if (
setColorMode(config.color_mode,
false) != IS_SUCCESS)
return;
650 if (config.image_width !=
cam_params_.image_width ||
654 needToReallocateBuffer =
true;
656 config.image_left, config.image_top,
false) != IS_SUCCESS) {
663 config.image_left, config.image_top,
false) != IS_SUCCESS)
return;
667 if (config.subsampling !=
cam_params_.subsampling) {
668 needToReallocateBuffer =
true;
669 if (
setSubsampling(config.subsampling,
false) != IS_SUCCESS)
return;
673 needToReallocateBuffer =
true;
674 if (
setBinning(config.binning,
false) != IS_SUCCESS)
return;
677 if (config.sensor_scaling !=
cam_params_.sensor_scaling) {
678 needToReallocateBuffer =
true;
684 if (needToReallocateBuffer) {
686 needToReallocateBuffer =
false;
690 if (!config.auto_exposure) {
691 config.auto_frame_rate =
false;
693 if (config.auto_frame_rate) {
694 config.auto_gain =
false;
705 if (config.master_gain !=
cam_params_.master_gain ||
710 config.auto_gain =
false;
713 if (
setGain(config.auto_gain, config.master_gain,
714 config.red_gain, config.green_gain,
715 config.blue_gain, config.gain_boost) != IS_SUCCESS)
return;
717 if (config.software_gamma !=
cam_params_.software_gamma) {
722 if (config.pixel_clock !=
cam_params_.pixel_clock) {
726 if (config.auto_frame_rate !=
cam_params_.auto_frame_rate ||
728 if (
setFrameRate(config.auto_frame_rate, config.frame_rate) != IS_SUCCESS)
return;
731 if (config.output_rate !=
cam_params_.output_rate) {
732 if (!config.auto_frame_rate) {
733 config.output_rate = std::min(config.output_rate, config.frame_rate);
743 if (config.auto_exposure !=
cam_params_.auto_exposure ||
744 config.auto_exposure_reference !=
cam_params_.auto_exposure_reference ||
746 if (
setExposure(config.auto_exposure, config.auto_exposure_reference, config.exposure) != IS_SUCCESS)
return;
749 if (config.auto_white_balance !=
cam_params_.auto_white_balance ||
750 config.white_balance_red_offset !=
cam_params_.white_balance_red_offset ||
751 config.white_balance_blue_offset !=
cam_params_.white_balance_blue_offset) {
752 if (
setWhiteBalance(config.auto_white_balance, config.white_balance_red_offset,
753 config.white_balance_blue_offset) != IS_SUCCESS)
return;
765 if (config.flash_delay !=
cam_params_.flash_delay ||
766 config.flash_duration !=
cam_params_.flash_duration) {
770 INT flash_delay = config.flash_delay;
771 UINT flash_duration =
static_cast<UINT
>(config.flash_duration);
774 config.flash_delay = flash_delay;
775 config.flash_duration =
static_cast<int>(flash_duration);
780 (config.gpio1 == 4 && ((config.pwm_freq !=
cam_params_.pwm_freq) || (config.pwm_duty_cycle !=
cam_params_.pwm_duty_cycle)))) {
781 if (
setGpioMode(1, config.gpio1, config.pwm_freq, config.pwm_duty_cycle) != IS_SUCCESS)
return;
784 (config.gpio2 == 4 && ((config.pwm_freq !=
cam_params_.pwm_freq) || (config.pwm_duty_cycle !=
cam_params_.pwm_duty_cycle)))) {
785 if (
setGpioMode(2, config.gpio2, config.pwm_freq, config.pwm_duty_cycle) != IS_SUCCESS)
return;
793 if (restartFrameGrabber) {
810 dft_mode_str <<
"\n(THIS IS A CODING ERROR, PLEASE CONTACT PACKAGE AUTHOR)");
835 INT is_err = IS_SUCCESS;
844 IS_GET_ENABLE_AUTO_SENSOR_GAIN, &pval1, &pval2)) != IS_SUCCESS &&
846 IS_GET_ENABLE_AUTO_GAIN, &pval1, &pval2)) != IS_SUCCESS) {
847 ERROR_STREAM(
"Failed to query auto gain mode for UEye camera '" <<
854 IS_IGNORE_PARAMETER, IS_IGNORE_PARAMETER, IS_IGNORE_PARAMETER);
856 IS_IGNORE_PARAMETER, IS_IGNORE_PARAMETER, IS_IGNORE_PARAMETER);
858 IS_IGNORE_PARAMETER, IS_IGNORE_PARAMETER, IS_IGNORE_PARAMETER);
860 IS_IGNORE_PARAMETER, IS_IGNORE_PARAMETER, IS_IGNORE_PARAMETER);
862 query = is_SetGainBoost(
cam_handle_, IS_GET_SUPPORTED_GAINBOOST);
863 if(query == IS_SET_GAINBOOST_ON) {
864 query = is_SetGainBoost(
cam_handle_, IS_GET_GAINBOOST);
865 if (query == IS_SET_GAINBOOST_ON) {
867 }
else if (query == IS_SET_GAINBOOST_OFF) {
871 "] (" <<
err2str(query) <<
")");
879 sizeof(
cam_params_.software_gamma))) != IS_SUCCESS) {
881 "] (" <<
err2str(is_err) <<
")");
886 IS_GET_ENABLE_AUTO_SENSOR_SHUTTER, &pval1, &pval2)) != IS_SUCCESS &&
888 IS_GET_ENABLE_AUTO_SHUTTER, &pval1, &pval2)) != IS_SUCCESS) {
890 "] (" <<
err2str(is_err) <<
")");
895 if ((is_err = is_SetAutoParameter (
cam_handle_, IS_GET_AUTO_REFERENCE,
896 &
cam_params_.auto_exposure_reference, 0)) != IS_SUCCESS) {
898 "] (" <<
err2str(is_err) <<
")");
901 if ((is_err = is_Exposure(
cam_handle_, IS_EXPOSURE_CMD_GET_EXPOSURE,
904 "] (" <<
err2str(is_err) <<
")");
909 IS_GET_ENABLE_AUTO_SENSOR_WHITEBALANCE, &pval1, &pval2)) != IS_SUCCESS &&
911 IS_GET_ENABLE_AUTO_WHITEBALANCE, &pval1, &pval2)) != IS_SUCCESS) {
913 "] (" <<
err2str(is_err) <<
")");
919 IS_GET_AUTO_WB_OFFSET, &pval1, &pval2)) != IS_SUCCESS) {
920 ERROR_STREAM(
"Failed to query auto white balance red/blue channel offsets for [" <<
924 cam_params_.white_balance_red_offset =
static_cast<int>(pval1);
925 cam_params_.white_balance_blue_offset =
static_cast<int>(pval2);
927 IO_FLASH_PARAMS currFlashParams;
928 if ((is_err = is_IO(
cam_handle_, IS_IO_CMD_FLASH_GET_PARAMS,
929 (
void*) &currFlashParams,
sizeof(IO_FLASH_PARAMS))) != IS_SUCCESS) {
930 ERROR_STREAM(
"Could not retrieve current flash parameter info for [" <<
934 cam_params_.flash_delay = currFlashParams.s32Delay;
935 cam_params_.flash_duration =
static_cast<int>(currFlashParams.u32Duration);
938 IS_GET_ENABLE_AUTO_SENSOR_FRAMERATE, &pval1, &pval2)) != IS_SUCCESS &&
940 IS_GET_ENABLE_AUTO_FRAMERATE, &pval1, &pval2)) != IS_SUCCESS) {
942 "] (" <<
err2str(is_err) <<
")");
949 "] (" <<
err2str(is_err) <<
")");
954 if ((is_err = is_PixelClock(
cam_handle_, IS_PIXELCLOCK_CMD_GET,
955 (
void*) &currPixelClock,
sizeof(currPixelClock))) != IS_SUCCESS) {
957 "] (" <<
err2str(is_err) <<
")");
960 cam_params_.pixel_clock =
static_cast<int>(currPixelClock);
962 INT currROP = is_SetRopEffect(
cam_handle_, IS_GET_ROP_EFFECT, 0, 0);
963 cam_params_.flip_upd = ((currROP & IS_SET_ROP_MIRROR_UPDOWN) == IS_SET_ROP_MIRROR_UPDOWN);
964 cam_params_.flip_lr = ((currROP & IS_SET_ROP_MIRROR_LEFTRIGHT) == IS_SET_ROP_MIRROR_LEFTRIGHT);
976 INT is_err = IS_SUCCESS;
997 INT is_err = IS_SUCCESS;
1009 sensor_msgs::SetCameraInfo::Response& rsp) {
1013 rsp.status_message = (rsp.success) ?
1014 "successfully wrote camera info to file" :
1015 "failed to write camera info to file";
1021 #ifdef DEBUG_PRINTOUT_FRAME_GRAB_RATES 1026 double startGrabSum = 0;
1027 double grabbedFrameSum = 0;
1028 double startGrabSumSqrd = 0;
1029 double grabbedFrameSumSqrd = 0;
1030 unsigned int startGrabCount = 0;
1031 unsigned int grabbedFrameCount = 0;
1038 int prevNumSubscribers = 0;
1039 int currNumSubscribers = 0;
1044 if (currNumSubscribers > 0 && prevNumSubscribers <= 0) {
1069 UINT flash_duration =
static_cast<unsigned int>(
cam_params_.flash_duration);
1073 cam_params_.flash_duration =
static_cast<int>(flash_duration);
1077 }
else if (currNumSubscribers <= 0 && prevNumSubscribers > 0) {
1085 prevNumSubscribers = currNumSubscribers;
1097 #ifdef DEBUG_PRINTOUT_FRAME_GRAB_RATES 1100 if (startGrabCount > 1) {
1101 startGrabSum += (currStartGrab - prevStartGrab).toSec() * 1000.0;
1102 startGrabSumSqrd += ((currStartGrab - prevStartGrab).toSec() * 1000.0)*((currStartGrab - prevStartGrab).toSec() * 1000.0);
1104 prevStartGrab = currStartGrab;
1109 static_cast<INT>(2000) :
static_cast<INT
>(1000.0 /
cam_params_.frame_rate * 2);
1112 sensor_msgs::ImagePtr img_msg_ptr(
new sensor_msgs::Image(
ros_image_));
1113 sensor_msgs::CameraInfoPtr cam_info_msg_ptr(
new sensor_msgs::CameraInfo(
ros_cam_info_));
1124 #ifdef DEBUG_PRINTOUT_FRAME_GRAB_RATES 1125 grabbedFrameCount++;
1127 if (grabbedFrameCount > 1) {
1128 grabbedFrameSum += (currGrabbedFrame - prevGrabbedFrame).toSec() * 1000.0;
1129 grabbedFrameSumSqrd += ((currGrabbedFrame - prevGrabbedFrame).toSec() * 1000.0)*((currGrabbedFrame - prevGrabbedFrame).toSec() * 1000.0);
1131 prevGrabbedFrame = currGrabbedFrame;
1133 if (grabbedFrameCount > 1) {
1134 WARN_STREAM(
"\nPre-Grab: " << startGrabSum/startGrabCount <<
" +/- " <<
1135 sqrt(startGrabSumSqrd/startGrabCount - (startGrabSum/startGrabCount)*(startGrabSum/startGrabCount)) <<
" ms (" <<
1136 1000.0*startGrabCount/startGrabSum <<
"Hz)\n" <<
1137 "Post-Grab: " << grabbedFrameSum/grabbedFrameCount <<
" +/- " <<
1138 sqrt(grabbedFrameSumSqrd/grabbedFrameCount - (grabbedFrameSum/grabbedFrameCount)*(grabbedFrameSum/grabbedFrameCount)) <<
" ms (" <<
1139 1000.0*grabbedFrameCount/grabbedFrameSum <<
"Hz)\n" <<
1147 bool throttle_curr_frame =
false;
1154 uint64_t curr_output_frame_idx =
static_cast<uint64_t
>(std::floor(time_elapsed *
cam_params_.output_rate));
1156 throttle_curr_frame =
true;
1163 if (throttle_curr_frame)
continue;
1171 img_msg_ptr->header.seq = cam_info_msg_ptr->header.seq =
ros_frame_count_++;
1172 img_msg_ptr->header.frame_id = cam_info_msg_ptr->header.frame_id;
1211 { IS_CM_SENSOR_RAW12, sensor_msgs::image_encodings::BAYER_RGGB16 },
1212 { IS_CM_SENSOR_RAW16, sensor_msgs::image_encodings::BAYER_RGGB16 },
1215 { IS_CM_MONO12, sensor_msgs::image_encodings::MONO16 },
1216 { IS_CM_MONO16, sensor_msgs::image_encodings::MONO16 },
1221 { IS_CM_RGB10_UNPACKED, sensor_msgs::image_encodings::RGB16 },
1222 { IS_CM_BGR10_UNPACKED, sensor_msgs::image_encodings::BGR16 },
1223 { IS_CM_RGB12_UNPACKED, sensor_msgs::image_encodings::RGB16 },
1224 { IS_CM_BGR12_UNPACKED, sensor_msgs::image_encodings::BGR16 }
1233 ") is smaller than expected for [" <<
cam_name_ <<
"]: " <<
1234 "width (" <<
cam_aoi_.s32Width <<
") * bytes per pixel (" <<
1240 img.width =
static_cast<unsigned int>(
cam_aoi_.s32Width);
1241 img.height =
static_cast<unsigned int>(
cam_aoi_.s32Height);
1244 img.data.resize(img.height * img.step);
1248 "\n width: " << img.width <<
1249 "\n height: " << img.height <<
1250 "\n step: " << img.step <<
1251 "\n encoding: " << img.encoding);
1257 unpackCopy(img.data.data(),
cam_buffer_, img.height*
static_cast<unsigned int>(expected_row_stride));
1260 uint8_t* dst_ptr = img.data.data();
1262 for (INT row = 0; row <
cam_aoi_.s32Height; row++) {
1263 unpackCopy(dst_ptr, cam_buffer_ptr, static_cast<unsigned long>(expected_row_stride));
1265 dst_ptr += img.step;
1328 std_msgs::UInt64 timeout_msg;
virtual INT connectCam(int new_cam_ID=-1)
static constexpr unsigned int RECONFIGURE_STOP
ros::Time getImageTimestamp()
unsigned int ros_frame_count_
void loadIntrinsicsFile()
void publish(const sensor_msgs::Image &image, const sensor_msgs::CameraInfo &info) const
const char * processNextFrame(UINT timeout_ms)
INT setExposure(bool &auto_exposure, double &auto_exposure_reference, double &exposure_ms)
std::thread frame_grab_thread_
static const std::string colormode2name(INT mode)
static const std::function< void *(void *, void *, size_t)> getUnpackCopyFunc(INT color_mode)
bool fillMsgData(sensor_msgs::Image &img) const
virtual ~UEyeCamNodelet()
def readCalibration(file_name)
void publish(const boost::shared_ptr< M > &message) const
static constexpr int DEFAULT_IMAGE_WIDTH
INT setMirrorLeftRight(bool flip_vertical)
static constexpr int ANY_CAMERA
static const std::string DEFAULT_FRAME_NAME
dynamic_reconfigure::Server< ueye_cam::UEyeCamConfig > ReconfigureServer
const std::string BAYER_RGGB16
static constexpr int DEFAULT_PIXEL_CLOCK
ReconfigureServer * ros_cfg_
ros::Publisher timeout_pub_
uint32_t getNumSubscribers() const
INT setFlashParams(INT &delay_us, UINT &duration_us)
bool saveIntrinsicsFile()
INT setGpioMode(const INT &gpio, INT &mode, double &pwm_freq, double &pwm_duty_cycle)
virtual void handleTimeout()
INT setWhiteBalance(bool &auto_white_balance, INT &red_offset, INT &blue_offset)
INT setColorMode(std::string &mode, bool reallocate_buffer=true)
INT setMirrorUpsideDown(bool flip_horizontal)
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
boost::mutex output_rate_mutex_
static constexpr int DEFAULT_FLASH_DURATION
static const std::map< INT, std::string > ENCODING_DICTIONARY
ros::Time init_publish_time_
ros::NodeHandle & getPrivateNodeHandle() const
std::string cam_params_filename_
bool setCamInfo(sensor_msgs::SetCameraInfo::Request &req, sensor_msgs::SetCameraInfo::Response &rsp)
#define DEBUG_STREAM(...)
INT setSensorScaling(double &rate, bool reallocate_buffer=true)
#define ERROR_STREAM(...)
INT setPixelClockRate(INT &clock_rate_mhz)
void configCallback(ueye_cam::UEyeCamConfig &config, uint32_t level)
CameraPublisher advertiseCamera(const std::string &base_topic, uint32_t queue_size, bool latch=false)
static INT name2colormode(const std::string &name)
static const char * err2str(INT error)
unsigned int cam_subsampling_rate_
static const std::string DEFAULT_CAMERA_NAME
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
INT setSubsampling(int &rate, bool reallocate_buffer=true)
double cam_sensor_scaling_rate_
virtual INT syncCamConfig(std::string dft_mode_str="mono8")
INT setResolution(INT &image_width, INT &image_height, INT &image_left, INT &image_top, bool reallocate_buffer=true)
bool writeCalibration(const std::string &file_name, const std::string &camera_name, const sensor_msgs::CameraInfo &cam_info)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
virtual INT syncCamConfig(std::string dft_mode_str="mono8")
ros::NodeHandle & getNodeHandle() const
INT parseROSParams(ros::NodeHandle &local_nh)
boost::recursive_mutex ros_cfg_mutex_
static constexpr double DEFAULT_EXPOSURE
sensor_msgs::Image ros_image_
static const std::string DEFAULT_CAMERA_TOPIC
sensor_msgs::CameraInfo ros_cam_info_
virtual INT disconnectCam()
static int numChannels(const std::string &encoding)
ueye_cam::UEyeCamConfig cam_params_
std::string timeout_topic_
std::string cam_intr_filename_
uint64_t prev_output_frame_idx_
bool getParam(const std::string &key, std::string &s) const
ros::Time getImageTickTimestamp()
unsigned long long int timeout_count_
uint64_t init_clock_tick_
INT setBinning(int &rate, bool reallocate_buffer=true)
INT setFrameRate(bool &auto_frame_rate, double &frame_rate_hz)
unsigned int cam_binning_rate_
ROSCPP_DECL void shutdown()
static const std::string DEFAULT_COLOR_MODE
const std::string BAYER_RGGB8
static int bitDepth(const std::string &encoding)
bool hasParam(const std::string &key) const
virtual INT disconnectCam()
static constexpr double DEFAULT_FRAME_RATE
static constexpr int DEFAULT_IMAGE_HEIGHT
unsigned int cam_buffer_size_
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
bool getClockTick(uint64_t *tick)
void setParam(const std::string &key, const XmlRpc::XmlRpcValue &v) const
image_transport::CameraPublisher ros_cam_pub_
INT setSoftwareGamma(INT &software_gamma)
std::string getTopic() const
static const std::string DEFAULT_TIMEOUT_TOPIC
INT loadCamConfig(std::string filename, bool ignore_load_failure=true)
ros::ServiceServer set_cam_info_srv_
INT setGain(bool &auto_gain, INT &master_gain_prc, INT &red_gain_prc, INT &green_gain_prc, INT &blue_gain_prc, bool &gain_boost)