planar_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/planar_pointcloud_simulator.h"
00037 #include <image_geometry/pinhole_camera_model.h>
00038 
00039 namespace jsk_pcl_ros
00040 {
00041   PlanarPointCloudSimulator::PlanarPointCloudSimulator()
00042   {
00043 
00044   }
00045 
00046   PlanarPointCloudSimulator::~PlanarPointCloudSimulator()
00047   {
00048 
00049   }
00050 
00051   void PlanarPointCloudSimulator::generate(
00052     const sensor_msgs::CameraInfo& info, double distance,
00053     pcl::PointCloud<pcl::PointXYZ>& cloud)
00054   {
00055     image_geometry::PinholeCameraModel model;
00056     model.fromCameraInfo(info);
00057     cloud.points.resize(info.width * info.height);
00058     cloud.is_dense = true;
00059     for (size_t j = 0; j < info.height; j++) {
00060       for (size_t i = 0; i < info.width; i++) {
00061         cv::Point3d ray = model.projectPixelTo3dRay(cv::Point2d(i, j));
00062         pcl::PointXYZ p;
00063         p.x = ray.x * distance;
00064         p.y = ray.y * distance;
00065         p.z = ray.z * distance;
00066         cloud.points[j * info.width + i] = p;
00067       }
00068     }
00069     cloud.width = info.width;
00070     cloud.height = info.height;
00071   }
00072 
00073   void PlanarPointCloudSimulatorNodelet::onInit()
00074   {
00075     DiagnosticNodelet::onInit();
00076     srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
00077     typename dynamic_reconfigure::Server<Config>::CallbackType f =
00078       boost::bind (&PlanarPointCloudSimulatorNodelet::configCallback, this, _1, _2);
00079     srv_->setCallback (f);
00080 
00081     pub_ = advertise<sensor_msgs::PointCloud2>(
00082       *pnh_, "output", 1);
00083   }
00084 
00085   void PlanarPointCloudSimulatorNodelet::subscribe()
00086   {
00087     sub_ = pnh_->subscribe(
00088       "input", 1, &PlanarPointCloudSimulatorNodelet::generate, this);
00089   }
00090 
00091   void PlanarPointCloudSimulatorNodelet::unsubscribe()
00092   {
00093     sub_.shutdown();
00094   }
00095 
00096   void PlanarPointCloudSimulatorNodelet::configCallback(
00097     Config &config, uint32_t level)
00098   {
00099     boost::mutex::scoped_lock lock(mutex_);
00100     distance_ = config.distance;
00101   }
00102   
00103   void PlanarPointCloudSimulatorNodelet::generate(
00104     const sensor_msgs::CameraInfo::ConstPtr& info_msg)
00105   {
00106     boost::mutex::scoped_lock lock(mutex_);
00107     pcl::PointCloud<pcl::PointXYZ>::Ptr
00108       cloud(new pcl::PointCloud<pcl::PointXYZ>);
00109     impl_.generate(*info_msg, distance_, *cloud);
00110     sensor_msgs::PointCloud2 ros_cloud;
00111     pcl::toROSMsg(*cloud, ros_cloud);
00112     ros_cloud.header = info_msg->header;
00113     pub_.publish(ros_cloud);
00114   }
00115   
00116 }
00117 
00118 #include <pluginlib/class_list_macros.h>
00119 PLUGINLIB_EXPORT_CLASS (jsk_pcl_ros::PlanarPointCloudSimulatorNodelet,
00120                         nodelet::Nodelet);


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