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 #include <ueye/CameraNode.h>
00036
00037 namespace ueye
00038 {
00039
00040 const std::string configFileName(Camera &cam)
00041 {
00042 std::stringstream ss;
00043 ss << "Cal-" << cam.getCameraName() << "-" << cam.getZoom() << "-" << cam.getCameraSerialNo() << ".txt";
00044 return ss.str();
00045 }
00046
00047 CameraNode::CameraNode(ros::NodeHandle node, ros::NodeHandle priv_nh) :
00048 srv_(priv_nh), it_(node)
00049 {
00050 running_ = false;
00051 configured_ = false;
00052 force_streaming_ = false;
00053 auto_exposure_ = false;
00054 auto_gain_ = false;
00055 trigger_mode_ = zoom_ = -1;
00056
00057
00058 const char *version;
00059 int major, minor, build;
00060 if (cam_.checkVersion(major, minor, build, version)) {
00061 ROS_INFO("Loaded uEye SDK %s.", version);
00062 } else {
00063 ROS_WARN("Loaded uEye SDK %d.%d.%d. Expecting %s.", major, minor, build, version);
00064 }
00065
00066
00067 int num_cameras = cam_.getNumberOfCameras();
00068 if (num_cameras > 0) {
00069 if (num_cameras == 1) {
00070 ROS_INFO("Found 1 uEye camera.");
00071 } else {
00072 ROS_INFO("Found %d uEye cameras.", num_cameras);
00073 }
00074 } else {
00075 ROS_ERROR("Found 0 uEye cameras.");
00076 ros::shutdown();
00077 return;
00078 }
00079
00080
00081 int id = 0;
00082 if (priv_nh.getParam("serialNo", id)) {
00083 if (!cam_.openCameraSerNo(id)) {
00084 ROS_ERROR("Failed to open uEye camera with serialNo: %u.", id);
00085 ros::shutdown();
00086 return;
00087 }
00088 } else if (priv_nh.getParam("deviceId", id)) {
00089 if (!cam_.openCameraDevId(id)) {
00090 ROS_ERROR("Failed to open uEye camera with deviceId: %u.", id);
00091 ros::shutdown();
00092 return;
00093 }
00094 } else {
00095 priv_nh.getParam("cameraId", id);
00096 if (!cam_.openCameraCamId(id)) {
00097 ROS_ERROR("Failed to open uEye camera with cameraId: %u.", id);
00098 ros::shutdown();
00099 return;
00100 }
00101 }
00102 ROS_INFO("Opened camera %s %u", cam_.getCameraName(), cam_.getCameraSerialNo());
00103
00104
00105 dynamic_reconfigure::Server<monoConfig>::CallbackType f = boost::bind(&CameraNode::reconfig, this, _1, _2);
00106 srv_.setCallback(f);
00107
00108
00109 srv_cam_info_ = node.advertiseService("set_camera_info", &CameraNode::setCameraInfo, this);
00110
00111
00112 pub_stream_ = it_.advertiseCamera("image_raw", 0);
00113
00114
00115 timer_ = node.createTimer(ros::Duration(1 / 5.0), &CameraNode::timerCallback, this);
00116 }
00117
00118 CameraNode::~CameraNode()
00119 {
00120 closeCamera();
00121 }
00122
00123 void CameraNode::handlePath(std::string &path)
00124 {
00125
00126 if (path.length() == 0) {
00127 path = ros::package::getPath("ueye");
00128 }
00129
00130
00131 unsigned int length = path.length();
00132 if (length > 0) {
00133 if (path.c_str()[length - 1] == '/') {
00134 path = path.substr(0, length - 1);
00135 }
00136 }
00137 config_path_ = path;
00138 }
00139 void CameraNode::reconfig(monoConfig &config, uint32_t level)
00140 {
00141 force_streaming_ = config.force_streaming;
00142 handlePath(config.config_path);
00143
00144
00145 if (trigger_mode_ != config.trigger) {
00146 stopCamera();
00147 TriggerMode mode;
00148 switch (config.trigger) {
00149 case mono_TGR_HARDWARE_RISING:
00150 mode = TRIGGER_LO_HI;
00151 break;
00152 case mono_TGR_HARDWARE_FALLING:
00153 mode = TRIGGER_HI_LO;
00154 break;
00155 case mono_TGR_AUTO:
00156 default:
00157 mode = TRIGGER_OFF;
00158 break;
00159 }
00160 if (!cam_.setTriggerMode(mode)) {
00161 cam_.setTriggerMode(TRIGGER_OFF);
00162 config.trigger = mono_TGR_AUTO;
00163 }
00164 }
00165 trigger_mode_ = config.trigger;
00166
00167
00168 uEyeColor color;
00169 switch (config.color) {
00170 default:
00171 case mono_COLOR_MONO8:
00172 color = MONO8;
00173 break;
00174 case mono_COLOR_MONO16:
00175 color = MONO16;
00176 break;
00177 case mono_COLOR_YUV:
00178 color = YUV;
00179 break;
00180 case mono_COLOR_YCbCr:
00181 color = YCbCr;
00182 break;
00183 case mono_COLOR_BGR5:
00184 color = BGR5;
00185 break;
00186 case mono_COLOR_BGR565:
00187 color = BGR565;
00188 break;
00189 case mono_COLOR_BGR8:
00190 color = BGR8;
00191 break;
00192 case mono_COLOR_BGRA8:
00193 color = BGRA8;
00194 break;
00195 case mono_COLOR_BGRY8:
00196 color = BGRY8;
00197 break;
00198 case mono_COLOR_RGB8:
00199 color = RGB8;
00200 break;
00201 case mono_COLOR_RGBA8:
00202 color = RGBA8;
00203 break;
00204 case mono_COLOR_RGBY8:
00205 color = RGBY8;
00206 break;
00207 }
00208 if (cam_.getColorMode() != color) {
00209 cam_.setColorMode(color);
00210 }
00211
00212
00213 if (auto_gain_ && !config.auto_gain) {
00214 config.gain = cam_.getHardwareGain();
00215 }
00216 auto_gain_ = config.auto_gain;
00217 if (auto_exposure_ && !config.auto_exposure) {
00218 config.exposure_time = cam_.getExposure();
00219 }
00220 auto_exposure_ = config.auto_exposure;
00221
00222
00223 if (cam_.getHardwareGamma() != config.hardware_gamma) {
00224 cam_.setHardwareGamma(&config.hardware_gamma);
00225 }
00226
00227
00228 if (cam_.getGainBoost() != config.gain_boost) {
00229 cam_.setGainBoost(&config.gain_boost);
00230 }
00231
00232
00233 if (cam_.getAutoGain() != config.auto_gain) {
00234 cam_.setAutoGain(&config.auto_gain);
00235 }
00236 if (!config.auto_gain) {
00237 cam_.setHardwareGain(&config.gain);
00238 }
00239
00240
00241 if (cam_.getZoom() != config.zoom) {
00242 cam_.setZoom(&config.zoom);
00243 }
00244
00245
00246 if (cam_.getPixelClock() != config.pixel_clock) {
00247 cam_.setPixelClock(&config.pixel_clock);
00248 }
00249
00250
00251 cam_.setFrameRate(&config.frame_rate);
00252
00253
00254 if (cam_.getAutoExposure() != config.auto_exposure) {
00255 cam_.setAutoExposure(&config.auto_exposure);
00256 }
00257 if (!config.auto_exposure) {
00258 cam_.setExposure(&config.exposure_time);
00259 }
00260
00261
00262 if (zoom_ != config.zoom) {
00263 zoom_ = config.zoom;
00264 loadIntrinsics();
00265 }
00266
00267 msg_camera_info_.header.frame_id = config.frame_id;
00268 configured_ = true;
00269 }
00270
00271 void CameraNode::timerCallback(const ros::TimerEvent& event)
00272 {
00273 if ((pub_stream_.getNumSubscribers() > 0) || force_streaming_) {
00274 startCamera();
00275 } else {
00276 stopCamera();
00277 }
00278 }
00279
00280
00281
00282 bool CameraNode::setCameraInfo(sensor_msgs::SetCameraInfo::Request& req, sensor_msgs::SetCameraInfo::Response& rsp)
00283 {
00284 ROS_INFO("New camera info received");
00285 sensor_msgs::CameraInfo &info = req.camera_info;
00286 info.header.frame_id = msg_camera_info_.header.frame_id;
00287
00288
00289 unsigned int height = cam_.getHeight();
00290 unsigned int width = cam_.getWidth();
00291
00292 if (info.width != width || info.height != height) {
00293 rsp.success = false;
00294 rsp.status_message = (boost::format("Camera_info resolution %ix%i does not match current video "
00295 "setting, camera running at resolution %ix%i.") % info.width % info.height
00296 % width % height).str();
00297 ROS_ERROR("%s", rsp.status_message.c_str());
00298 return true;
00299 }
00300
00301 std::string camname = cam_.getCameraName();
00302 std::stringstream ini_stream;
00303 if (!camera_calibration_parsers::writeCalibrationIni(ini_stream, camname, info)) {
00304 rsp.status_message = "Error formatting camera_info for storage.";
00305 rsp.success = false;
00306 } else {
00307 std::string ini = ini_stream.str();
00308 std::fstream param_file;
00309 std::string filename = config_path_ + "/" + configFileName(cam_);
00310 param_file.open(filename.c_str(), std::ios::in | std::ios::out | std::ios::trunc);
00311
00312 if (param_file.is_open()) {
00313 param_file << ini.c_str();
00314 param_file.close();
00315
00316 msg_camera_info_ = info;
00317 rsp.success = true;
00318 } else {
00319 rsp.success = false;
00320 rsp.status_message = "file write failed";
00321 }
00322 }
00323 if (!rsp.success) {
00324 ROS_ERROR("%s", rsp.status_message.c_str());
00325 }
00326 return true;
00327 }
00328
00329
00330 void CameraNode::loadIntrinsics()
00331 {
00332 char buffer[12800];
00333
00334 std::string MyPath = config_path_ + "/" + configFileName(cam_);
00335 std::fstream param_file;
00336 param_file.open(MyPath.c_str(), std::ios::in);
00337
00338 if (param_file.is_open()) {
00339 param_file.read(buffer, 12800);
00340 param_file.close();
00341 }
00342
00343
00344 std::string camera_name;
00345 if (camera_calibration_parsers::parseCalibrationIni(buffer, camera_name, msg_camera_info_)) {
00346 ROS_INFO("Loaded calibration for camera '%s'", camera_name.c_str());
00347 } else {
00348 ROS_WARN("Failed to load intrinsics for camera from file");
00349 }
00350 }
00351
00352
00353 sensor_msgs::ImagePtr CameraNode::processFrame(IplImage* frame, sensor_msgs::CameraInfoPtr &info)
00354 {
00355 msg_camera_info_.header.stamp = ros::Time::now();
00356 msg_camera_info_.header.seq++;
00357 msg_camera_info_.roi.x_offset = 0;
00358 msg_camera_info_.roi.y_offset = 0;
00359 msg_camera_info_.height = cam_.getHeight();
00360 msg_camera_info_.width = cam_.getWidth();
00361 msg_camera_info_.roi.width = 0;
00362 msg_camera_info_.roi.height = 0;
00363 sensor_msgs::CameraInfoPtr msg(new sensor_msgs::CameraInfo(msg_camera_info_));
00364 info = msg;
00365
00366 converter_.header = msg_camera_info_.header;
00367 converter_.encoding = Camera::colorModeToString(cam_.getColorMode());
00368 converter_.image = frame;
00369 return converter_.toImageMsg();
00370 }
00371
00372
00373 void CameraNode::publishImage(IplImage * frame)
00374 {
00375 sensor_msgs::CameraInfoPtr info;
00376 sensor_msgs::ImagePtr img = processFrame(frame, info);
00377 pub_stream_.publish(img, info);
00378 }
00379
00380 void CameraNode::startCamera()
00381 {
00382 if (running_ || !configured_)
00383 return;
00384 cam_.startVideoCapture(boost::bind(&CameraNode::publishImage, this, _1));
00385 ROS_INFO("Started video stream.");
00386 running_ = true;
00387 }
00388
00389 void CameraNode::stopCamera()
00390 {
00391 if (!running_)
00392 return;
00393 cam_.stopVideoCapture();
00394 ROS_INFO("Stopped video stream.");
00395 running_ = false;
00396 }
00397
00398 void CameraNode::closeCamera()
00399 {
00400 stopCamera();
00401 cam_.closeCamera();
00402 }
00403
00404 }