spherical_pointcloud_simulator_nodelet.cpp
Go to the documentation of this file.
00001 // -*- mode: c++ -*-
00002 /*********************************************************************
00003  * Software License Agreement (BSD License)
00004  *
00005  *  Copyright (c) 2015, JSK Lab
00006  *  All rights reserved.
00007  *
00008  *  Redistribution and use in source and binary forms, with or without
00009  *  modification, are permitted provided that the following conditions
00010  *  are met:
00011  *
00012  *   * Redistributions of source code must retain the above copyright
00013  *     notice, this list of conditions and the following disclaimer.
00014  *   * Redistributions in binary form must reproduce the above
00015  *     copyright notice, this list of conditions and the following
00016  *     disclaimer in the documentation and/o2r other materials provided
00017  *     with the distribution.
00018  *   * Neither the name of the JSK Lab nor the names of its
00019  *     contributors may be used to endorse or promote products derived
00020  *     from this software without specific prior written permission.
00021  *
00022  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033  *  POSSIBILITY OF SUCH DAMAGE.
00034  *********************************************************************/
00035 #define BOOST_PARAMETER_MAX_ARITY 7
00036 #include "jsk_pcl_ros/spherical_pointcloud_simulator.h"
00037 
00038 namespace jsk_pcl_ros
00039 {
00040   void SphericalPointCloudSimulator::onInit()
00041   {
00042     DiagnosticNodelet::onInit();
00043     pnh_->getParam("frame_id", frame_id_);
00044     rotate_velocity_ = 0.5;
00045     srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
00046     typename dynamic_reconfigure::Server<Config>::CallbackType f =
00047       boost::bind (&SphericalPointCloudSimulator::configCallback, this, _1, _2);
00048     srv_->setCallback (f);
00049 
00050     double rate;
00051     if (pnh_->getParam("rate", rate)) {
00052       timer_ = pnh_->createTimer(
00053         ros::Duration(1 / rate), boost::bind(
00054           &SphericalPointCloudSimulator::timerCallback,
00055           this,
00056           _1));
00057     }
00058     pub_ = advertise<sensor_msgs::PointCloud2>(
00059       *pnh_, "output", 1);
00060   }
00061 
00062   void SphericalPointCloudSimulator::subscribe()
00063   {
00064     sub_ = pnh_->subscribe(
00065       "input", 1, &SphericalPointCloudSimulator::generate, this);
00066   }
00067 
00068   void SphericalPointCloudSimulator::unsubscribe()
00069   {
00070     sub_.shutdown();
00071   }
00072 
00073   void SphericalPointCloudSimulator::configCallback(
00074     Config &config, uint32_t level)
00075   {
00076     boost::mutex::scoped_lock lock(mutex_);
00077     r_ = config.r;
00078     min_phi_ = config.min_phi;
00079     max_phi_ = config.max_phi;
00080     scan_range_ = config.scan_range;
00081     scan_num_ = config.scan_num;
00082     fps_ = config.fps;
00083   }
00084 
00085   void SphericalPointCloudSimulator::timerCallback(
00086     const ros::TimerEvent& event)
00087   {
00088     // make up pointcloud and call generate
00089     sensor_msgs::PointCloud2 dummy_cloud;
00090     dummy_cloud.header.stamp = ros::Time::now();
00091     dummy_cloud.header.frame_id = "map"; // default is map
00092     generate(boost::make_shared<sensor_msgs::PointCloud2>(dummy_cloud));
00093   }
00094   
00095   void SphericalPointCloudSimulator::generate(
00096     const sensor_msgs::PointCloud2::ConstPtr& msg)
00097   {
00098     boost::mutex::scoped_lock lock(mutex_);
00099     pcl::PointCloud<pcl::PointXYZ>::Ptr
00100       cloud (new pcl::PointCloud<pcl::PointXYZ>);
00101     // 40fps 
00102     int phi_num = 2 * M_PI / rotate_velocity_ * fps_;
00103     int point_num = phi_num * scan_num_;
00104     cloud->points.resize(point_num);
00105     int i = 0;
00106     for (int phi_i = 0; phi_i < phi_num; phi_i++) {
00107       double phi = (float)phi_i / phi_num * (max_phi_ - min_phi_) + min_phi_;
00108       Eigen::Affine3f trans = getPlane(phi);
00109       for (int theta_i = 0; theta_i < scan_num_; theta_i++) {
00110         double theta = theta_i * scan_range_ / scan_num_ - scan_range_ / 2.0;
00111         pcl::PointXYZ p = getPoint(r_, theta, trans);
00112         cloud->points[i] = p;
00113         i++;
00114       }
00115     }
00116     sensor_msgs::PointCloud2 ros_cloud;
00117     pcl::toROSMsg(*cloud, ros_cloud);
00118     ros_cloud.header.stamp = msg->header.stamp;
00119     if (!frame_id_.empty()) {
00120       ros_cloud.header.frame_id = frame_id_;
00121     }
00122     else {
00123       ros_cloud.header.frame_id = cloud->header.frame_id;
00124     }
00125     pub_.publish(ros_cloud);
00126   }
00127 
00128   Eigen::Affine3f SphericalPointCloudSimulator::getPlane(double phi)
00129   {
00130     Eigen::Vector3f norm(0, sin(phi), cos(phi));
00131     Eigen::Quaternionf rot;
00132     rot.setFromTwoVectors(Eigen::Vector3f::UnitZ(), norm);
00133     Eigen::Affine3f trans = Eigen::Affine3f::Identity();
00134     trans = trans * rot;
00135     return trans;
00136   }
00137 
00138   pcl::PointXYZ SphericalPointCloudSimulator::getPoint(
00139     double r, double theta, const Eigen::Affine3f& trans)
00140   {
00141     Eigen::Vector3f local_p(r * cos(theta), r * sin(theta), 0);
00142     Eigen::Vector3f world_p = trans * local_p;
00143     pcl::PointXYZ p;
00144     p.getVector3fMap() = world_p;
00145     return p;
00146   }
00147   
00148 }
00149 
00150 #include <pluginlib/class_list_macros.h>
00151 PLUGINLIB_EXPORT_CLASS (
00152   jsk_pcl_ros::SphericalPointCloudSimulator, nodelet::Nodelet);


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Wed Sep 16 2015 04:36:48