node.cpp
Go to the documentation of this file.
00001 
00041 #include <sick_visionary_t_driver/driver.h>
00042 #include <ros/ros.h>
00043 #include <image_transport/image_transport.h>
00044 #include <sensor_msgs/image_encodings.h>
00045 #include <sensor_msgs/PointCloud2.h>
00046 #include <cv_bridge/cv_bridge.h>
00047 #include <boost/thread.hpp>
00048 #include <sensor_msgs/CameraInfo.h>
00049 #include <std_msgs/ByteMultiArray.h>
00050 
00052 const bool SUPPRESS_INVALID_POINTS = true;
00053 
00055 const uint16_t NARE_DISTANCE_VALUE = 0xffffU;
00056 image_transport::Publisher g_pub_depth, g_pub_confidence, g_pub_intensity;
00057 ros::Publisher g_pub_camera_info, g_pub_points, g_pub_ios;
00058 Driver_3DCS::Control *g_control = NULL;
00059 std::string g_frame_id;
00061 bool g_publish_all = false;
00062 
00063 boost::mutex g_mtx_data;
00064 boost::shared_ptr<Driver_3DCS::Data> g_data;
00065 
00066 void publish_frame(const Driver_3DCS::Data &data);
00067 
00068 void thr_publish_frame() {
00069         g_mtx_data.lock();
00070         publish_frame(*g_data);
00071         g_mtx_data.unlock();
00072 }
00073 
00074 void on_frame(const boost::shared_ptr<Driver_3DCS::Data> &data) {
00075         //update data in queue and
00076         //detach publishing data from network thread
00077         
00078         if(g_publish_all || g_mtx_data.try_lock()) {
00079                 if(g_publish_all)
00080                         g_mtx_data.lock();
00081                 g_data = data;
00082                 g_mtx_data.unlock();
00083                 
00084                 boost::thread thr(thr_publish_frame);
00085         }
00086         else
00087                 ROS_WARN("skipping frame");
00088 }
00089 
00090 void publish_frame(const Driver_3DCS::Data &data) {
00091         bool published_anything = false;
00092         
00093         sensor_msgs::ImagePtr msg;
00094         std_msgs::Header header;
00095         header.stamp = ros::Time::now();
00096         header.frame_id = g_frame_id;
00097         
00098         if(g_pub_camera_info.getNumSubscribers()>0) {
00099                 published_anything = true;
00100                 
00101                 sensor_msgs::CameraInfo ci;
00102                 ci.header = header;
00103                 
00104                 ci.height = data.getCameraParameters().height;
00105                 ci.width  = data.getCameraParameters().width;
00106                 
00107                 ci.D.clear();
00108                 ci.D.resize(5,0);
00109                 ci.D[0] = data.getCameraParameters().k1;
00110                 ci.D[1] = data.getCameraParameters().k2;
00111                 
00112                 for(int i=0; i<9; i++) ci.K[i]=0;
00113                 ci.K[0] = data.getCameraParameters().fx;
00114                 ci.K[4] = data.getCameraParameters().fy;
00115                 ci.K[2] = data.getCameraParameters().cx;
00116                 ci.K[5] = data.getCameraParameters().cy;
00117                 
00118                 for(int i=0; i<12; i++)
00119                         ci.P[i] = 0;//data.getCameraParameters().cam2worldMatrix[i];
00120                 //TODO:....
00121                 ci.P[0] = data.getCameraParameters().fx;
00122                 ci.P[5] = data.getCameraParameters().fy;
00123                 ci.P[10] = 1;
00124                 ci.P[2] = data.getCameraParameters().cx;
00125                 ci.P[6] = data.getCameraParameters().cy;
00126                         
00127                 g_pub_camera_info.publish(ci);
00128         }
00129         
00130         if(g_pub_depth.getNumSubscribers()>0) {
00131                 published_anything = true;
00132                 
00133                 msg = cv_bridge::CvImage(std_msgs::Header(), sensor_msgs::image_encodings::TYPE_16UC1, data.get_distance()).toImageMsg();
00134                 msg->header = header;
00135                 g_pub_depth.publish(msg);
00136         }
00137         if(g_pub_confidence.getNumSubscribers()>0) {
00138                 published_anything = true;
00139                 
00140                 msg = cv_bridge::CvImage(std_msgs::Header(), sensor_msgs::image_encodings::TYPE_16UC1, data.get_confidence()).toImageMsg();
00141                 msg->header = header;
00142                 g_pub_confidence.publish(msg);
00143         }
00144         if(g_pub_intensity.getNumSubscribers()>0) {
00145                 published_anything = true;
00146                 
00147                 msg = cv_bridge::CvImage(std_msgs::Header(), sensor_msgs::image_encodings::TYPE_16UC1, data.get_intensity()).toImageMsg();
00148                 msg->header = header;
00149                 g_pub_intensity.publish(msg);
00150         }
00151         if(g_pub_points.getNumSubscribers()>0) {
00152                 published_anything = true;
00153                 
00154                 typedef sensor_msgs::PointCloud2 PointCloud;
00155                 
00156                 // Allocate new point cloud message
00157                 PointCloud::Ptr cloud_msg (new PointCloud);
00158                 cloud_msg->header = header; // Use depth image time stamp
00159                 cloud_msg->height = data.get_distance().rows;
00160                 cloud_msg->width  = data.get_distance().cols;
00161                 cloud_msg->is_dense = false;
00162                 cloud_msg->is_bigendian = false;
00163 
00164                 cloud_msg->fields.resize (5);
00165                 cloud_msg->fields[0].name = "x"; cloud_msg->fields[1].name = "y"; cloud_msg->fields[2].name = "z";
00166                 cloud_msg->fields[3].name = "confidence"; cloud_msg->fields[4].name = "intensity";
00167                 int offset = 0;
00168                 // All offsets are *4, as all field data types are float32
00169                 for (size_t d = 0; d < cloud_msg->fields.size (); ++d, offset += 4)
00170                 {
00171                         cloud_msg->fields[d].offset = offset;
00172                         cloud_msg->fields[d].datatype = (d<3) ? int(sensor_msgs::PointField::FLOAT32) : int(sensor_msgs::PointField::UINT16);
00173                         cloud_msg->fields[d].count  = 1;
00174                 }
00175                 cloud_msg->point_step = offset;
00176                 cloud_msg->row_step   = cloud_msg->point_step * cloud_msg->width;
00177                 cloud_msg->data.resize (cloud_msg->height * cloud_msg->width * cloud_msg->point_step);
00178 
00179         const float f2rc = data.getCameraParameters().f2rc / 1000.f; // since f2rc is given in [mm], but the pcl message wants [m]
00180                 
00181                 uint16_t *pDepth, *pConf, *pInt;
00182                 int cp=0;
00183                 for(int i = 0; i < data.get_distance().rows; ++i)
00184                 {
00185                         pDepth = (uint16_t*)(data.get_distance()  .data + (data.get_distance()  .step*i) );
00186                         pConf  = (uint16_t*)(data.get_confidence().data + (data.get_confidence().step*i) );
00187                         pInt   = (uint16_t*)(data.get_intensity() .data + (data.get_intensity() .step*i) );
00188                         
00189                         for (int j = 0; j < data.get_distance().cols; ++j, ++cp)
00190                         {
00191                                 if(pDepth[j]==0 || pDepth[j]==NARE_DISTANCE_VALUE) {
00192                                         const float bad_point = std::numeric_limits<float>::quiet_NaN();
00193                                         memcpy (&cloud_msg->data[cp * cloud_msg->point_step + cloud_msg->fields[0].offset], &bad_point, sizeof (float));
00194                                         memcpy (&cloud_msg->data[cp * cloud_msg->point_step + cloud_msg->fields[1].offset], &bad_point, sizeof (float));
00195                                         memcpy (&cloud_msg->data[cp * cloud_msg->point_step + cloud_msg->fields[2].offset], &bad_point, sizeof (float));
00196                                 }
00197                                 else {
00198                                         float xp = (data.getCameraParameters().cx - j) / data.getCameraParameters().fx;
00199                                         float yp = (data.getCameraParameters().cy - i) / data.getCameraParameters().fy;
00200 
00201                                         // Correction of the lens distortion
00202                                         float r2 = (xp * xp + yp * yp);
00203                                         float r4 = r2 * r2;
00204                                         float k = 1 + data.getCameraParameters().k1 * r2 + data.getCameraParameters().k2 * r4;
00205                                         xp = xp * k;
00206                                         yp = yp * k;
00207 
00208                                         // Calculation of the distances
00209                                         float s0 = std::sqrt(xp*xp + yp*yp + 1.f) * 1000.f;
00210 
00211                                         // Calculation of the Cartesian coordinates
00212                                         const float ox = xp * pDepth[j] / s0;
00213                                         const float oy = yp * pDepth[j] / s0;
00214                     const float oz = pDepth[j] / s0 - f2rc;
00215                                         
00216                                         memcpy (&cloud_msg->data[cp * cloud_msg->point_step + cloud_msg->fields[0].offset], &ox, sizeof (float));
00217                                         memcpy (&cloud_msg->data[cp * cloud_msg->point_step + cloud_msg->fields[1].offset], &oy, sizeof (float));
00218                                         memcpy (&cloud_msg->data[cp * cloud_msg->point_step + cloud_msg->fields[2].offset], &oz, sizeof (float));
00219                                 }
00220                                 
00221                                 memcpy (&cloud_msg->data[cp * cloud_msg->point_step + cloud_msg->fields[3].offset], &pConf[j], sizeof (uint16_t));
00222                                 memcpy (&cloud_msg->data[cp * cloud_msg->point_step + cloud_msg->fields[4].offset], &pInt [j], sizeof (uint16_t));
00223                         }
00224                 }
00225                 
00226                 g_pub_points.publish(cloud_msg);
00227         }
00228         
00229         if(!published_anything) {
00230                 if(g_control) g_control->stopStream();
00231         }
00232 }
00233 
00234 void _on_new_subscriber() {        
00235         ROS_DEBUG("Got new subscriber");
00236 
00237         if(!g_control) return;
00238 
00239         bool r=g_control->startStream(); // tell the device to start streaming data
00240         ROS_ASSERT(r);
00241 }
00242 
00243 void on_new_subscriber_ros(const ros::SingleSubscriberPublisher& pub) {        
00244         _on_new_subscriber();
00245 }
00246 
00247 void on_new_subscriber_it(const image_transport::SingleSubscriberPublisher& pub) {        
00248         _on_new_subscriber();
00249 }
00250 
00251 int main(int argc, char **argv) {
00252         ros::console::set_logger_level(ROSCONSOLE_DEFAULT_NAME, ros::console::levels::Debug);
00253         ros::init(argc, argv, "driver_3DCS");
00254         ros::NodeHandle nh("~");
00255         
00256         bool r;
00257         boost::asio::io_service io_service;
00258         
00259         //default parameters
00260         std::string remote_device_ip="192.168.1.10";
00261         g_frame_id = "camera";
00262         
00263         ros::param::get("~remote_device_ip", remote_device_ip);
00264         ros::param::get("~frame_id", g_frame_id);
00265         ros::param::get("~prevent_frame_skipping", g_publish_all);
00266         
00267         Driver_3DCS::Control control(io_service, remote_device_ip);
00268         r=control.open();
00269         ROS_ASSERT(r);
00270         r=control.initStream();
00271         ROS_ASSERT(r);
00272         
00273         boost::thread thr(boost::bind(&boost::asio::io_service::run, &io_service));
00274         
00275         Driver_3DCS::Streaming device(io_service, remote_device_ip);
00276         device.getSignal().connect( boost::bind(&on_frame, _1) );
00277         r=device.openStream();
00278         ROS_ASSERT(r);
00279         
00280         g_control = &control;
00281         
00282         //make me public (after init.)
00283         
00284         image_transport::ImageTransport it(nh);
00285         g_pub_depth = it.advertise("depth", 1, (image_transport::SubscriberStatusCallback)on_new_subscriber_it, image_transport::SubscriberStatusCallback());
00286         g_pub_points = nh.advertise<sensor_msgs::PointCloud2>("points", 2, (ros::SubscriberStatusCallback)on_new_subscriber_ros, ros::SubscriberStatusCallback());
00287         g_pub_confidence = it.advertise("confidence", 1, (image_transport::SubscriberStatusCallback)on_new_subscriber_it, image_transport::SubscriberStatusCallback());
00288         g_pub_intensity = it.advertise("intensity", 1, (image_transport::SubscriberStatusCallback)on_new_subscriber_it, image_transport::SubscriberStatusCallback());
00289         g_pub_camera_info = nh.advertise<sensor_msgs::CameraInfo>("camera_info", 1, (ros::SubscriberStatusCallback)on_new_subscriber_ros, ros::SubscriberStatusCallback());
00290         g_pub_ios = nh.advertise<std_msgs::ByteMultiArray>("ios", 1, (ros::SubscriberStatusCallback)on_new_subscriber_ros, ros::SubscriberStatusCallback());
00291         
00292         //wait til end of exec.
00293         ros::spin();
00294 
00295         io_service.stop();
00296         device.closeStream();
00297         control.close();
00298         
00299         g_pub_depth.shutdown();
00300         g_pub_confidence.shutdown();
00301         g_pub_intensity.shutdown();
00302         g_pub_camera_info.shutdown();
00303         g_pub_points.shutdown();
00304         g_pub_ios.shutdown();
00305 
00306         return 0;
00307 }


sick_visionary_t_driver
Author(s): Joshua Hampp
autogenerated on Sat Jun 8 2019 19:04:06