transform.cc
Go to the documentation of this file.
00001 /*
00002  *  Copyright (C) 2009, 2010 Austin Robot Technology, Jack O'Quin
00003  *  Copyright (C) 2011 Jesse Vera
00004  *  Copyright (C) 2012 Austin Robot Technology, Jack O'Quin
00005  *  License: Modified BSD Software License Agreement
00006  *
00007  *  $Id$
00008  */
00009 
00021 #include "velodyne_pointcloud/transform.h"
00022 
00023 #include <velodyne_pointcloud/pointcloudXYZIR.h>
00024 #include <velodyne_pointcloud/organized_cloudXYZIR.h>
00025 
00026 namespace velodyne_pointcloud
00027 {
00029   Transform::Transform(ros::NodeHandle node, ros::NodeHandle private_nh):
00030     tf_prefix_(tf::getPrefixParam(private_nh)),
00031     data_(new velodyne_rawdata::RawData),
00032     first_rcfg_call(true)
00033   {
00034     boost::optional<velodyne_pointcloud::Calibration> calibration = data_->setup(private_nh);
00035     if(calibration)
00036     {
00037       ROS_DEBUG_STREAM("Calibration file loaded.");
00038       config_.num_lasers = static_cast<uint16_t>(calibration.get().num_lasers);
00039     }
00040     else
00041     {
00042       ROS_ERROR_STREAM("Could not load calibration file!");
00043     }
00044 
00045     config_.target_frame = config_.fixed_frame = "velodyne";
00046     tf_ptr_ = boost::make_shared<tf::TransformListener>();
00047 
00048     if(config_.organize_cloud)
00049     {
00050       container_ptr = boost::shared_ptr<OrganizedCloudXYZIR>(
00051           new OrganizedCloudXYZIR(config_.max_range, config_.min_range, config_.target_frame, config_.fixed_frame,
00052                                   config_.num_lasers, data_->scansPerPacket(), tf_ptr_));
00053     }
00054     else
00055     {
00056       container_ptr = boost::shared_ptr<PointcloudXYZIR>(
00057           new PointcloudXYZIR(config_.max_range, config_.min_range,
00058                               config_.target_frame, config_.fixed_frame,
00059                               data_->scansPerPacket(), tf_ptr_));
00060     }
00061 
00062     // advertise output point cloud (before subscribing to input data)
00063     output_ =
00064       node.advertise<sensor_msgs::PointCloud2>("velodyne_points", 10);
00065 
00066     srv_ = boost::make_shared<dynamic_reconfigure::Server<TransformNodeCfg>> (private_nh);
00067     dynamic_reconfigure::Server<TransformNodeCfg>::CallbackType f;
00068     f = boost::bind (&Transform::reconfigure_callback, this, _1, _2);
00069     srv_->setCallback (f);
00070 
00071     // subscribe to VelodyneScan packets using transform filter
00072     velodyne_scan_.subscribe(node, "velodyne_packets", 10);
00073     tf_filter_ptr_ = boost::shared_ptr<tf::MessageFilter<velodyne_msgs::VelodyneScan> >(
00074             new tf::MessageFilter<velodyne_msgs::VelodyneScan>(velodyne_scan_, *tf_ptr_, config_.target_frame, 10));
00075     tf_filter_ptr_->registerCallback(boost::bind(&Transform::processScan, this, _1));
00076     private_nh.param<std::string>("fixed_frame", config_.fixed_frame, "odom");
00077 
00078     // Diagnostics
00079     diagnostics_.setHardwareID("Velodyne Transform");
00080     // Arbitrary frequencies since we don't know which RPM is used, and are only
00081     // concerned about monitoring the frequency.
00082     diag_min_freq_ = 2.0;
00083     diag_max_freq_ = 20.0;
00084     using namespace diagnostic_updater;
00085     diag_topic_.reset(new TopicDiagnostic("velodyne_points", diagnostics_,
00086                                           FrequencyStatusParam(&diag_min_freq_,
00087                                                                &diag_max_freq_,
00088                                                                0.1, 10),
00089                                           TimeStampStatusParam()));
00090 
00091   }
00092   
00093   void Transform::reconfigure_callback(
00094       velodyne_pointcloud::TransformNodeConfig &config, uint32_t level)
00095   {
00096     ROS_INFO_STREAM("Reconfigure request.");
00097     data_->setParameters(config.min_range, config.max_range,
00098                          config.view_direction, config.view_width);
00099     config_.target_frame = tf::resolve(tf_prefix_, config.frame_id);
00100     ROS_INFO_STREAM("Target frame ID now: " << config_.target_frame);
00101     config_.min_range = config.min_range;
00102     config_.max_range = config.max_range;
00103 
00104     boost::lock_guard<boost::mutex> guard(reconfigure_mtx_);
00105 
00106     if(first_rcfg_call || config.organize_cloud != config_.organize_cloud){
00107       first_rcfg_call = false;
00108       config_.organize_cloud = config.organize_cloud;
00109       if(config_.organize_cloud)
00110       {
00111         ROS_INFO_STREAM("Using the organized cloud format...");
00112         container_ptr = boost::shared_ptr<OrganizedCloudXYZIR>(
00113             new OrganizedCloudXYZIR(config_.max_range, config_.min_range,
00114                                     config_.target_frame, config_.fixed_frame,
00115                                     config_.num_lasers, data_->scansPerPacket()));
00116       }
00117       else
00118       {
00119         container_ptr = boost::shared_ptr<PointcloudXYZIR>(
00120             new PointcloudXYZIR(config_.max_range, config_.min_range,
00121                                 config_.target_frame, config_.fixed_frame,
00122                                 data_->scansPerPacket()));
00123       }
00124     }
00125     container_ptr->configure(config_.max_range, config_.min_range, config_.fixed_frame, config_.target_frame);
00126   }
00127 
00133   void
00134     Transform::processScan(const velodyne_msgs::VelodyneScan::ConstPtr &scanMsg)
00135   {
00136     if (output_.getNumSubscribers() == 0)         // no one listening?
00137       return;                                     // avoid much work
00138 
00139     boost::lock_guard<boost::mutex> guard(reconfigure_mtx_);
00140 
00141     // allocate a point cloud with same time and frame ID as raw data
00142     container_ptr->setup(scanMsg);
00143 
00144     // process each packet provided by the driver
00145     for (size_t i = 0; i < scanMsg->packets.size(); ++i)
00146     {
00147       container_ptr->computeTransformation(scanMsg->packets[i].stamp);
00148       data_->unpack(scanMsg->packets[i], *container_ptr);
00149     }
00150     // publish the accumulated cloud message
00151     output_.publish(container_ptr->finishCloud());
00152 
00153     diag_topic_->tick(scanMsg->header.stamp);
00154     diagnostics_.update();
00155   }
00156 
00157 } // namespace velodyne_pointcloud


velodyne_pointcloud
Author(s): Jack O'Quin, Piyush Khandelwal, Jesse Vera, Sebastian Pütz
autogenerated on Wed Jul 3 2019 19:32:23