pointcloud_model_generator_node.cpp
Go to the documentation of this file.
1 // -*- mode: c++ -*-
2 /*********************************************************************
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2015, JSK Lab
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/o2r other materials provided
17  * with the distribution.
18  * * Neither the name of the JSK Lab nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *********************************************************************/
35 #include <ros/ros.h>
37 #include <jsk_footstep_planner/PointCloudModelGeneratorConfig.h>
38 #include <sensor_msgs/PointCloud2.h>
40 #include <dynamic_reconfigure/server.h>
41 
42 using namespace jsk_footstep_planner;
43 
44 double hole_rate;
45 std::string model;
47 void reconfigureCallback(PointCloudModelGeneratorConfig &config, uint32_t level)
48 {
49  boost::mutex::scoped_lock lock(mutex);
50  hole_rate = config.hole_rate;
51  model = config.model;
52 }
53 
54 
55 int main(int argc, char** argv)
56 {
57  ros::init(argc, argv, "pointcloud_model_generator_node");
58  ros::NodeHandle pnh("~");
59  ros::Rate r(1);
60  ros::Publisher pub_cloud = pnh.advertise<sensor_msgs::PointCloud2>("output", 1, true);
61  dynamic_reconfigure::Server<PointCloudModelGeneratorConfig> server;
62  server.setCallback(boost::bind(&reconfigureCallback, _1, _2));
63  while (ros::ok()) {
64  ros::spinOnce();
65  r.sleep();
66  {
67  boost::mutex::scoped_lock lock(mutex);
69  pcl::PointCloud<pcl::PointNormal> cloud;
70  gen.generate(model, cloud, hole_rate);
71  sensor_msgs::PointCloud2 ros_cloud;
72  pcl::toROSMsg(cloud, ros_cloud);
73  ros_cloud.header.frame_id = "odom";
74  ros_cloud.header.stamp = ros::Time::now();
75  pub_cloud.publish(ros_cloud);
76  }
77  }
78  return 0;
79 }
void publish(const boost::shared_ptr< M > &message) const
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
server
std::string model
pcl::PointCloud< pcl::PointNormal >::Ptr cloud
ROSCPP_DECL bool ok()
virtual void generate(const std::string &model_name, pcl::PointCloud< PointT > &output, double hole_rate=0.0)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
ros::Publisher pub_cloud
void reconfigureCallback(PointCloudModelGeneratorConfig &config, uint32_t level)
bool sleep()
void toROSMsg(const pcl::PointCloud< T > &cloud, sensor_msgs::Image &msg)
mutex_t * lock
r
static Time now()
just a pointcloud generator for sample usage
boost::mutex mutex
int main(int argc, char **argv)
ROSCPP_DECL void spinOnce()


jsk_footstep_planner
Author(s): Ryohei Ueda
autogenerated on Fri May 14 2021 02:51:52