With the help of others I have developed a nodelet to display a horizonal projection of a laserscan with a pan/tilt Kinect camera. This nodelet is intended to work with the other pointcloud_to_laserscan nodelets, providing a choice of two laserscan projection types. Here is the source code with detailed instructions appended at the end ...
SOURCE cloud_to_scanHoriz.cpp:
/*
* Copyright (c) 2010, Willow Garage, Inc.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions are met:
*
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in the
* documentation and/or other materials provided with the distribution.
* * Neither the name of the Willow Garage, Inc. nor the names of its
* contributors may be used to endorse or promote products derived from
* this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
* ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
* LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
* CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
* SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
* INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
* CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
* ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*/
#include "ros/ros.h"
#include "pluginlib/class_list_macros.h"
#include "nodelet/nodelet.h"
#include "sensor_msgs/LaserScan.h"
#include "pcl/point_cloud.h"
#include "pcl_ros/point_cloud.h"
#include "pcl/point_types.h"
#include "pcl/ros/conversions.h"
#include "pcl_ros/transforms.h"
#include "tf/transform_listener.h"
#include "tf/message_filter.h"
#include "message_filters/subscriber.h"
namespace pointcloud_to_laserscan
{
typedef pcl::PointCloud<pcl::PointXYZ> PointCloud;
class CloudToScanHoriz : public nodelet::Nodelet
{
public:
//Constructor
CloudToScanHoriz(): min_height_(0.10), max_height_(0.75), baseFrame("/base_footprint"), laserFrame("/camera_tower")
{
};
private:
double min_height_, max_height_;
std::string baseFrame; //ground plane referenced by laser
std::string laserFrame; //pan frame simulating projected laser
bool result;
tf::TransformListener tfListener;
message_filters::Subscriber<PointCloud> cloudSubscriber;
tf::MessageFilter<PointCloud> *tfFilter;
ros::Publisher laserPublisher;
//Nodelet initialization
virtual void onInit()
{
ros::NodeHandle& nh = getNodeHandle();
ros::NodeHandle& private_nh = getPrivateNodeHandle();
private_nh.getParam("min_height", min_height_);
private_nh.getParam("max_height", max_height_);
private_nh.getParam("base_frame", baseFrame);
private_nh.getParam("laser_frame", laserFrame);
NODELET_INFO("CloudToScanHoriz min_height: %f, max_height: %f", min_height_, max_height_);
NODELET_INFO("CloudToScanHoriz baseFrame: %s, laserFrame: %s", baseFrame.c_str(), laserFrame.c_str());
//Set up to process new pointCloud and tf data together
cloudSubscriber.subscribe(nh, "cloud_in", 5);
tfFilter = new tf::MessageFilter<PointCloud>(cloudSubscriber, tfListener, laserFrame, 1);
tfFilter->registerCallback(boost::bind(&CloudToScanHoriz::callback, this, _1));
tfFilter->setTolerance(ros::Duration(0.01));
laserPublisher = nh.advertise<sensor_msgs::LaserScan>("laserScanHoriz", 10);
};
//Pointcloud and tf transform received
void callback(const PointCloud::ConstPtr& cloud_in)
{
PointCloud cloudTransformed;
sensor_msgs::LaserScanPtr ...
(more)