Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00016 #include "velodyne_pointcloud/convert.h"
00017
00018 #include <velodyne_pointcloud/pointcloudXYZIR.h>
00019 #include <velodyne_pointcloud/organized_cloudXYZIR.h>
00020
00021 namespace velodyne_pointcloud
00022 {
00024 Convert::Convert(ros::NodeHandle node, ros::NodeHandle private_nh):
00025 data_(new velodyne_rawdata::RawData()), first_rcfg_call(true)
00026 {
00027
00028 boost::optional<velodyne_pointcloud::Calibration> calibration = data_->setup(private_nh);
00029 if(calibration)
00030 {
00031 ROS_DEBUG_STREAM("Calibration file loaded.");
00032 config_.num_lasers = static_cast<uint16_t>(calibration.get().num_lasers);
00033 }
00034 else
00035 {
00036 ROS_ERROR_STREAM("Could not load calibration file!");
00037 }
00038
00039 if(config_.organize_cloud)
00040 {
00041 container_ptr_ = boost::shared_ptr<OrganizedCloudXYZIR>(
00042 new OrganizedCloudXYZIR(config_.max_range, config_.min_range,
00043 config_.target_frame, config_.fixed_frame,
00044 config_.num_lasers, data_->scansPerPacket()));
00045 }
00046 else
00047 {
00048 container_ptr_ = boost::shared_ptr<PointcloudXYZIR>(
00049 new PointcloudXYZIR(config_.max_range, config_.min_range,
00050 config_.target_frame, config_.fixed_frame,
00051 data_->scansPerPacket()));
00052 }
00053
00054
00055
00056 output_ =
00057 node.advertise<sensor_msgs::PointCloud2>("velodyne_points", 10);
00058
00059 srv_ = boost::make_shared <dynamic_reconfigure::Server<velodyne_pointcloud::
00060 CloudNodeConfig> > (private_nh);
00061 dynamic_reconfigure::Server<velodyne_pointcloud::CloudNodeConfig>::
00062 CallbackType f;
00063 f = boost::bind (&Convert::callback, this, _1, _2);
00064 srv_->setCallback (f);
00065
00066
00067 velodyne_scan_ =
00068 node.subscribe("velodyne_packets", 10,
00069 &Convert::processScan, (Convert *) this,
00070 ros::TransportHints().tcpNoDelay(true));
00071
00072
00073 diagnostics_.setHardwareID("Velodyne Convert");
00074
00075
00076 diag_min_freq_ = 2.0;
00077 diag_max_freq_ = 20.0;
00078 using namespace diagnostic_updater;
00079 diag_topic_.reset(new TopicDiagnostic("velodyne_points", diagnostics_,
00080 FrequencyStatusParam(&diag_min_freq_,
00081 &diag_max_freq_,
00082 0.1, 10),
00083 TimeStampStatusParam()));
00084 }
00085
00086 void Convert::callback(velodyne_pointcloud::CloudNodeConfig &config,
00087 uint32_t level)
00088 {
00089 ROS_INFO("Reconfigure Request");
00090 data_->setParameters(config.min_range, config.max_range, config.view_direction,
00091 config.view_width);
00092 config_.fixed_frame = config.fixed_frame;
00093 config_.target_frame = config.target_frame;
00094 config_.min_range = config.min_range;
00095 config_.max_range = config.max_range;
00096
00097 if(first_rcfg_call || config.organize_cloud != config_.organize_cloud){
00098 first_rcfg_call = false;
00099 config_.organize_cloud = config.organize_cloud;
00100 if(config_.organize_cloud)
00101 {
00102 ROS_INFO_STREAM("Using the organized cloud format...");
00103 container_ptr_ = boost::shared_ptr<OrganizedCloudXYZIR>(
00104 new OrganizedCloudXYZIR(config_.max_range, config_.min_range,
00105 config_.target_frame, config_.fixed_frame,
00106 config_.num_lasers, data_->scansPerPacket()));
00107 }
00108 else
00109 {
00110 container_ptr_ = boost::shared_ptr<PointcloudXYZIR>(
00111 new PointcloudXYZIR(config_.max_range, config_.min_range,
00112 config_.target_frame, config_.fixed_frame,
00113 data_->scansPerPacket()));
00114 }
00115 }
00116
00117 container_ptr_->configure(config_.max_range, config_.min_range, config_.fixed_frame, config_.target_frame);
00118
00119 }
00120
00122 void Convert::processScan(const velodyne_msgs::VelodyneScan::ConstPtr &scanMsg)
00123 {
00124 if (output_.getNumSubscribers() == 0)
00125 return;
00126
00127 boost::lock_guard<boost::mutex> guard(reconfigure_mtx_);
00128
00129 container_ptr_->setup(scanMsg);
00130
00131
00132 for (size_t i = 0; i < scanMsg->packets.size(); ++i)
00133 {
00134 data_->unpack(scanMsg->packets[i], *container_ptr_);
00135 }
00136
00137
00138 diag_topic_->tick(scanMsg->header.stamp);
00139 diagnostics_.update();
00140 output_.publish(container_ptr_->finishCloud());
00141 }
00142
00143 }