basler_tof_node.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright (C) 2017, DFKI GmbH
00003  * All rights reserved.
00004  *
00005  * Redistribution and use in source and binary forms, with or without
00006  * modification, are permitted provided that the following conditions are met:
00007  *
00008  *     * Redistributions of source code must retain the above copyright
00009  *       notice, this list of conditions and the following disclaimer.
00010  *     * Redistributions in binary form must reproduce the above copyright
00011  *       notice, this list of conditions and the following disclaimer in the
00012  *       documentation and/or other materials provided with the distribution.
00013  *     * Neither the name of DFKI GmbH nor the names of its
00014  *       contributors may be used to endorse or promote products derived from
00015  *       this software without specific prior written permission.
00016  *
00017  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00021  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00022  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00023  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00024  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00025  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00026  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00027  * POSSIBILITY OF SUCH DAMAGE.
00028  *
00029  *      Author:
00030  *         Martin Günther <martin.guenther@dfki.de>
00031  */
00032 
00033 #include <ConsumerImplHelper/ToFCamera.h>
00034 #include <GenTL/PFNC.h>
00035 #include <string>
00036 #include <iostream>
00037 #include <fstream>
00038 #include <iomanip>
00039 
00040 #include <ros/ros.h>
00041 #include <camera_info_manager/camera_info_manager.h>
00042 #include <sensor_msgs/Image.h>
00043 #include <sensor_msgs/CameraInfo.h>
00044 #include <sensor_msgs/image_encodings.h>
00045 #include <cv_bridge/cv_bridge.h>
00046 #include <opencv2/opencv.hpp>
00047 #include <pcl_ros/point_cloud.h>
00048 #include <pcl_conversions/pcl_conversions.h>
00049 
00050 #include <dynamic_reconfigure/server.h>
00051 #include <basler_tof/BaslerToFConfig.h>
00052 
00053 using namespace GenTLConsumerImplHelper;
00054 using namespace GenApi;
00055 using namespace std;
00056 
00057 ros::Publisher cloud_pub_;
00058 ros::Publisher intensity_pub_;
00059 ros::Publisher intensity_ci_pub_;
00060 ros::Publisher confidence_pub_;
00061 ros::Publisher confidence_ci_pub_;
00062 ros::Publisher depth_pub_;
00063 ros::Publisher depth_ci_pub_;
00064 std::string frame_id_;
00065 std::string device_id_;
00066 std::string camera_name_;
00067 CToFCamera camera_;
00068 
00069 boost::shared_ptr<camera_info_manager::CameraInfoManager> intensity_info_manager_;
00070 boost::shared_ptr<camera_info_manager::CameraInfoManager> confidence_info_manager_;
00071 boost::shared_ptr<camera_info_manager::CameraInfoManager> depth_info_manager_;
00072 
00073 
00074 bool publish(const BufferParts& parts, ros::Time acquisition_time)
00075 {
00076   if (parts.size() != 3)
00077   {
00078     ROS_ERROR("Expected 3 parts, got %zu!", parts.size());
00079     return false;
00080   }
00081 
00082   // If the point cloud is enabled, the first part always contains the point cloud data.
00083   if (parts[0].dataFormat != PFNC_Coord3D_ABC32f)
00084   {
00085     ROS_ERROR("Unexpected data format for the first image part. Coord3D_ABC32f is expected.");
00086     return false;
00087   }
00088 
00089   if (parts[1].dataFormat != PFNC_Mono16)
00090   {
00091     ROS_ERROR("Unexpected data format for the second image part. Mono16 is expected.");
00092     return false;
00093   }
00094 
00095   // ----- publish point cloud
00096   const size_t nPixel = parts[0].width * parts[0].height;
00097 
00098   pcl::PointCloud<pcl::PointXYZI>::Ptr cloud(new pcl::PointCloud<pcl::PointXYZI>());
00099   cloud->header.frame_id = frame_id_;
00100   cloud->header.stamp = pcl_conversions::toPCL(acquisition_time);
00101   cloud->width = parts[0].width;
00102   cloud->height = parts[0].height;
00103   cloud->is_dense = false;
00104   cloud->points.resize(nPixel);
00105 
00106   CToFCamera::Coord3D *pPoint = static_cast<CToFCamera::Coord3D*>(parts[0].pData);
00107   uint16_t *pIntensity = static_cast<uint16_t*>(parts[1].pData);
00108 
00109   for (size_t i = 0; i < nPixel; ++i)
00110   {
00111     pcl::PointXYZI &p = cloud->points[i];
00112     if (pPoint->IsValid())
00113     {
00114       p.x = 0.001f * pPoint->x;
00115       p.y = 0.001f * pPoint->y;
00116       p.z = 0.001f * pPoint->z;
00117       p.intensity = *pIntensity;
00118     }
00119     else
00120     {
00121       p.x = std::numeric_limits<float>::quiet_NaN();
00122       p.y = std::numeric_limits<float>::quiet_NaN();
00123       p.z = std::numeric_limits<float>::quiet_NaN();
00124     }
00125     pPoint++;
00126     pIntensity++;
00127   }
00128 
00129   cloud_pub_.publish(cloud);
00130 
00131   // ----- publish intensity image
00132   pIntensity = static_cast<uint16_t*>(parts[1].pData);
00133 
00134   cv_bridge::CvImage intensity_cvimg;
00135   intensity_cvimg.encoding = sensor_msgs::image_encodings::MONO16;
00136   intensity_cvimg.header.frame_id = frame_id_;
00137   intensity_cvimg.header.stamp = acquisition_time;
00138   intensity_cvimg.image = cv::Mat(parts[1].height, parts[1].width, CV_16UC1);
00139   intensity_cvimg.image.setTo(0);
00140 
00141   for (size_t i = 0; i < parts[1].height; i++)
00142   {
00143     for (size_t j = 0; j < parts[1].width; j++)
00144     {
00145       intensity_cvimg.image.at<unsigned short>(i, j) = static_cast<unsigned short>(*pIntensity);
00146       pIntensity++;
00147     }
00148   }
00149   // uncomment these two lines for cameracalibrator.py
00150   // intensity_cvimg.image.convertTo(intensity_cvimg.image, CV_8U, 1.0 / 256.0);
00151   // intensity_cvimg.encoding = sensor_msgs::image_encodings::MONO8;
00152 
00153   intensity_pub_.publish(intensity_cvimg.toImageMsg());
00154 
00155   sensor_msgs::CameraInfoPtr intensity_info_msg(new sensor_msgs::CameraInfo(intensity_info_manager_->getCameraInfo()));
00156   intensity_info_msg->header.stamp    = acquisition_time;
00157   intensity_info_msg->header.frame_id = frame_id_;
00158   intensity_ci_pub_.publish(intensity_info_msg);
00159 
00160   // ----- publish confidence image
00161   uint16_t *pConfidence = static_cast<uint16_t*>(parts[2].pData);
00162 
00163   cv_bridge::CvImage confidence_cvimg;
00164   confidence_cvimg.encoding = sensor_msgs::image_encodings::MONO16;
00165   confidence_cvimg.header.frame_id = frame_id_;
00166   confidence_cvimg.header.stamp = acquisition_time;
00167   confidence_cvimg.image = cv::Mat(parts[2].height, parts[2].width, CV_16UC1);
00168   confidence_cvimg.image.setTo(0);
00169 
00170   for (size_t i = 0; i < parts[2].height; i++)
00171   {
00172     for (size_t j = 0; j < parts[2].width; j++)
00173     {
00174       confidence_cvimg.image.at<unsigned short>(i, j) = static_cast<unsigned short>(*pConfidence);
00175       pConfidence++;
00176     }
00177   }
00178 
00179   confidence_pub_.publish(confidence_cvimg.toImageMsg());
00180 
00181   sensor_msgs::CameraInfoPtr confidence_info_msg(new sensor_msgs::CameraInfo(confidence_info_manager_->getCameraInfo()));
00182   confidence_info_msg->header.stamp    = acquisition_time;
00183   confidence_info_msg->header.frame_id = frame_id_;
00184   confidence_ci_pub_.publish(confidence_info_msg);
00185 
00186   // ----- publish depth image
00187   pPoint = static_cast<CToFCamera::Coord3D*>(parts[0].pData);
00188 
00189   cv_bridge::CvImage depth_cvimg;
00190   depth_cvimg.encoding = sensor_msgs::image_encodings::TYPE_16UC1;
00191   depth_cvimg.header.frame_id = frame_id_;
00192   depth_cvimg.header.stamp = acquisition_time;
00193   depth_cvimg.image = cv::Mat(parts[0].height, parts[0].width, CV_16UC1);
00194   depth_cvimg.image.setTo(0);
00195 
00196   for (size_t i = 0; i < parts[0].height; i++)
00197   {
00198     for (size_t j = 0; j < parts[0].width; j++)
00199     {
00200       depth_cvimg.image.at<uint16_t>(i, j) = static_cast<uint16_t>(pPoint->z);   // can be NaN; should be in mm
00201       pPoint++;
00202     }
00203   }
00204 
00205   depth_pub_.publish(depth_cvimg.toImageMsg());
00206 
00207   sensor_msgs::CameraInfoPtr depth_info_msg(new sensor_msgs::CameraInfo(depth_info_manager_->getCameraInfo()));
00208   depth_info_msg->header.stamp    = acquisition_time;
00209   depth_info_msg->header.frame_id = frame_id_;
00210   depth_ci_pub_.publish(depth_info_msg);
00211 
00212   return true;
00213 }
00214 
00215 void round_to_increment_int(int &param, int increment)
00216 {
00217   param = ((param + increment / 2) / increment) * increment;
00218 }
00219 
00220 void round_to_increment_double(double &param, double increment)
00221 {
00222   param = (int)((param + increment / 2) / increment) * increment;
00223 }
00224 
00225 void update_config(basler_tof::BaslerToFConfig &new_config, uint32_t level)
00226 {
00227   // round to increments
00228   round_to_increment_int(new_config.exposure_time, 100);
00229   round_to_increment_double(new_config.exposure_agility, 0.1);
00230   round_to_increment_int(new_config.confidence_threshold, 16);
00231   round_to_increment_int(new_config.temporal_strength, 5);
00232   round_to_increment_int(new_config.outlier_tolerance, 16);
00233 
00234   CFloatPtr(camera_.GetParameter("AcquisitionFrameRate"))->SetValue(new_config.frame_rate);
00235 
00236   if (new_config.exposure_auto)
00237   {
00238     CEnumerationPtr(camera_.GetParameter("ExposureAuto"))->FromString("Continuous");
00239 
00240     // Agility and Delay are only valid when exposure_auto is "true"
00241     CFloatPtr(camera_.GetParameter("Agility"))->SetValue(new_config.exposure_agility);
00242     CIntegerPtr(camera_.GetParameter("Delay"))->SetValue(new_config.exposure_delay);
00243   }
00244   else
00245   {
00246     CEnumerationPtr(camera_.GetParameter("ExposureAuto"))->FromString("Off");
00247 
00248     // ExposureTime is only valid when exposure_auto is "false"
00249     CFloatPtr(camera_.GetParameter("ExposureTime"))->SetValue(new_config.exposure_time);
00250   }
00251 
00252   CIntegerPtr(camera_.GetParameter("ConfidenceThreshold"))->SetValue(new_config.confidence_threshold);
00253   CBooleanPtr(camera_.GetParameter("FilterSpatial"))->SetValue(new_config.spatial_filter);
00254   CBooleanPtr(camera_.GetParameter("FilterTemporal"))->SetValue(new_config.temporal_filter);
00255   CIntegerPtr(camera_.GetParameter("FilterStrength"))->SetValue(new_config.temporal_strength);
00256   CIntegerPtr(camera_.GetParameter("OutlierTolerance"))->SetValue(new_config.outlier_tolerance);
00257 }
00258 
00259 int main(int argc, char* argv[])
00260 {
00261   ros::init(argc, argv, "basler_tof_node");
00262   ros::NodeHandle n;
00263   ros::NodeHandle pn("~");
00264   ros::NodeHandle intensity_nh("intensity");
00265   ros::NodeHandle confidence_nh("confidence");
00266   ros::NodeHandle depth_nh("depth");
00267 
00268   pn.param("frame_id", frame_id_, std::string("camera_optical_frame"));
00269   if (!pn.getParam("device_id", device_id_))
00270   {
00271     ROS_WARN("~device_id is not set! Using first device.");
00272     device_id_ = "#1";
00273   }
00274 
00275   cloud_pub_ = n.advertise<pcl::PointCloud<pcl::PointXYZI> > ("points", 10);
00276   intensity_pub_ = n.advertise<sensor_msgs::Image>("intensity/image_raw", 10);
00277   confidence_pub_ = n.advertise<sensor_msgs::Image>("confidence/image_raw", 10);
00278   depth_pub_ = n.advertise<sensor_msgs::Image>("depth/image_raw", 10);
00279   intensity_ci_pub_ = n.advertise<sensor_msgs::CameraInfo>("intensity/camera_info", 10);
00280   confidence_ci_pub_ = n.advertise<sensor_msgs::CameraInfo>("confidence/camera_info", 10);
00281   depth_ci_pub_ = n.advertise<sensor_msgs::CameraInfo>("depth/camera_info", 10);
00282 
00283   intensity_info_manager_ = boost::make_shared<camera_info_manager::CameraInfoManager>(intensity_nh);
00284   confidence_info_manager_ = boost::make_shared<camera_info_manager::CameraInfoManager>(confidence_nh);
00285   depth_info_manager_ = boost::make_shared<camera_info_manager::CameraInfoManager>(depth_nh);
00286 
00287   int exitCode = EXIT_FAILURE;
00288 
00289   try
00290   {
00291     CToFCamera::InitProducer();
00292 
00293     if (device_id_ == "#1")
00294     {
00295       ROS_INFO("Opening first camera.");
00296       camera_.OpenFirstCamera();
00297     }
00298     else
00299     {
00300       CameraList cameraList = camera_.EnumerateCameras();
00301       bool found = false;
00302       for (CameraList::const_iterator it = cameraList.begin(); it != cameraList.end(); ++it)
00303       {
00304         ROS_INFO("Found camera device with serial: %s", it->strSerialNumber.c_str());
00305         if (it->strSerialNumber == device_id_)
00306         {
00307           ROS_INFO("Serial matches device_id, opening camera.");
00308           found = true;
00309           camera_.Open(*it);
00310           break;
00311         }
00312       }
00313       if (!found)
00314       {
00315         ROS_FATAL("No camera with device_id '%s' found, exiting!", device_id_.c_str());
00316         return EXIT_FAILURE;
00317       }
00318     }
00319 
00320     std::string camera_name_ = camera_.GetCameraInfo().strModelName
00321                                + "_" + camera_.GetCameraInfo().strSerialNumber;
00322     if (!intensity_info_manager_->setCameraName(camera_name_) ||
00323         !confidence_info_manager_->setCameraName(camera_name_) ||
00324         !depth_info_manager_->setCameraName(camera_name_))
00325     {
00326       ROS_WARN_STREAM("[" << camera_name_
00327                       << "] name not valid"
00328                       << " for camera_info_manager");
00329     }
00330 
00331     std::string camera_info_url;
00332     if (pn.getParam("camera_info_url", camera_info_url))
00333     {
00334       if (!intensity_info_manager_->validateURL(camera_info_url) ||
00335           !confidence_info_manager_->validateURL(camera_info_url) ||
00336           !depth_info_manager_->validateURL(camera_info_url))
00337       {
00338         ROS_WARN("camera_info_url invalid: %s", camera_info_url.c_str());
00339       }
00340       else
00341       {
00342         intensity_info_manager_->loadCameraInfo(camera_info_url);
00343         confidence_info_manager_->loadCameraInfo(camera_info_url);
00344         depth_info_manager_->loadCameraInfo(camera_info_url);
00345       }
00346     }
00347 
00348     ROS_INFO_STREAM("[" << camera_name_ << "] opened.");
00349 
00350     ROS_INFO_STREAM("DeviceVendorName:      " << CStringPtr(camera_.GetParameter("DeviceVendorName"))->GetValue());
00351     ROS_INFO_STREAM("DeviceModelName:       " << CStringPtr(camera_.GetParameter("DeviceModelName"))->GetValue());
00352     ROS_INFO_STREAM("DeviceVersion:         " << CStringPtr(camera_.GetParameter("DeviceVersion"))->GetValue());
00353     ROS_INFO_STREAM("DeviceFirmwareVersion: " << CStringPtr(camera_.GetParameter("DeviceFirmwareVersion"))->GetValue());
00354     ROS_INFO_STREAM("DeviceDriverVersion:   " << CStringPtr(camera_.GetParameter("DeviceDriverVersion"))->GetValue());
00355     ROS_INFO_STREAM("DeviceSerialNumber:    " << CStringPtr(camera_.GetParameter("DeviceSerialNumber"))->GetValue());
00356 
00357     ROS_INFO_STREAM("DeviceCalibVersion:    " << CIntegerPtr(camera_.GetParameter("DeviceCalibVersion"))->GetValue());
00358     ROS_INFO_STREAM("DeviceCalibState:      " << CEnumerationPtr(camera_.GetParameter("DeviceCalibState"))->ToString());
00359     ROS_INFO_STREAM("DeviceCalibOffset:     " << CIntegerPtr(camera_.GetParameter("DeviceCalibOffset"))->GetValue());
00360 
00361     ROS_INFO_STREAM("DeviceTemperature:     " << CFloatPtr(camera_.GetParameter("DeviceTemperature"))->GetValue() << " degrees C");
00362 
00363 
00364     // Parameterize the camera to send 3D coordinates and intensity data
00365     CEnumerationPtr ptrImageComponentSelector = camera_.GetParameter("ImageComponentSelector");
00366     CBooleanPtr ptrImageComponentEnable = camera_.GetParameter("ImageComponentEnable");
00367     CEnumerationPtr ptrPixelFormat = camera_.GetParameter("PixelFormat");
00368 
00369     ptrImageComponentSelector->FromString("Range");
00370     ptrImageComponentEnable->SetValue(true);
00371     ptrPixelFormat->FromString("Coord3D_ABC32f");
00372 
00373     ptrImageComponentSelector->FromString("Intensity");
00374     ptrImageComponentEnable->SetValue(true);
00375     ptrPixelFormat->FromString("Mono16");
00376 
00377     ptrImageComponentSelector->FromString("Confidence");
00378     ptrImageComponentEnable->SetValue(true);
00379     ptrPixelFormat->FromString("Confidence16");
00380 
00381     dynamic_reconfigure::Server<basler_tof::BaslerToFConfig> dynamic_reconfigure_server;
00382     dynamic_reconfigure::Server<basler_tof::BaslerToFConfig>::CallbackType f;
00383     f = boost::bind(&update_config, _1, _2);
00384     dynamic_reconfigure_server.setCallback(f);
00385 
00386     while (ros::ok())
00387     {
00388       ros::spinOnce();
00389 
00390       // Acquire one single image
00391       BufferParts parts;
00392       GrabResultPtr ptrGrabResult = camera_.GrabSingleImage(1000, &parts);
00393 
00394       // Save 3D data
00395       if (ptrGrabResult->status == GrabResult::Ok)
00396       {
00397         publish(parts, ros::Time::now());
00398       }
00399       else
00400       {
00401         ROS_ERROR("Failed to grab an image.");
00402       }
00403     }
00404 
00405     camera_.Close();
00406     exitCode = EXIT_SUCCESS;
00407   }
00408   catch (GenICam::GenericException& e)
00409   {
00410     ROS_ERROR_STREAM("Exception occurred: " << endl << e.GetDescription());
00411   }
00412 
00413   if (CToFCamera::IsProducerInitialized())
00414     CToFCamera::TerminateProducer();  // Won't throw any exceptions
00415 
00416   return exitCode;
00417 }
00418 


basler_tof
Author(s): Martin Guenther
autogenerated on Tue Aug 15 2017 02:43:10