pointcloud_to_laserscan_node.cpp
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2010-2012, Willow Garage, Inc.
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of Willow Garage, Inc. nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  *
00034  *
00035  */
00036 
00037 /*
00038  * Author: Paul Bovbel
00039  */
00040 
00041 #include <ros/ros.h>
00042 #include <nodelet/loader.h>
00043 
00044 int main(int argc, char **argv){
00045   ros::init(argc, argv, "pointcloud_to_laserscan_node");
00046   ros::NodeHandle private_nh("~");
00047   int concurrency_level;
00048   private_nh.param<int>("concurrency_level", concurrency_level, 0);
00049 
00050   nodelet::Loader nodelet;
00051   nodelet::M_string remap(ros::names::getRemappings());
00052   nodelet::V_string nargv;
00053   std::string nodelet_name = ros::this_node::getName();
00054   nodelet.load(nodelet_name, "pointcloud_to_laserscan/pointcloud_to_laserscan_nodelet", remap, nargv);
00055 
00056   boost::shared_ptr<ros::MultiThreadedSpinner> spinner;
00057   if(concurrency_level) {
00058     spinner.reset(new ros::MultiThreadedSpinner(concurrency_level));
00059   }else{
00060     spinner.reset(new ros::MultiThreadedSpinner());
00061   }
00062   spinner->spin();
00063   return 0;
00064 
00065 }


pointcloud_to_laserscan
Author(s): Tully Foote
autogenerated on Wed Aug 26 2015 15:25:52