pcd_to_pointcloud.cpp
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2009, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Willow Garage, Inc. nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *
34  * $Id: pcd_to_pointcloud.cpp 33238 2010-03-11 00:46:58Z rusu $
35  *
36  */
37 
46 // ROS core
47 #include <ros/ros.h>
49 
50 #include <string>
51 #include <sstream>
52 
53 // helper function to return parsed parameter or default value
54 template <typename T>
55 T get_param(std::string const& name, T default_value) {
56  T value;
57  ros::param::param<T>(name, value, default_value);
58  return value;
59 }
60 
63  // the topic to publish at, will be overwritten to give the remapped name
64  std::string cloud_topic;
65  // source file name, will be overwritten to produce actually configured file
66  std::string file_name;
67  // republish interval in seconds
68  double interval;
69  // tf2 frame_id
70  std::string frame_id;
71  // latched topic enabled/disabled
72  bool latch;
73  // pointcloud message and publisher
74  sensor_msgs::PointCloud2 cloud;
76  // timer to handle republishing
78 
79  void publish() {
80  ROS_DEBUG_STREAM_ONCE("Publishing pointcloud");
81  ROS_DEBUG_STREAM_ONCE(" * number of points: " << cloud.width * cloud.height);
82  ROS_DEBUG_STREAM_ONCE(" * frame_id: " << cloud.header.frame_id);
83  ROS_DEBUG_STREAM_ONCE(" * topic_name: " << cloud_topic);
84  int num_subscribers = pub.getNumSubscribers();
85  if (num_subscribers > 0) {
86  ROS_DEBUG("Publishing data to %d subscribers.", num_subscribers);
87  }
88  // update timestamp and publish
89  cloud.header.stamp = ros::Time::now();
90  pub.publish(cloud);
91  }
92 
94  // just re-publish
95  publish();
96  }
97 
98 public:
100  : cloud_topic("cloud_pcd"), file_name(""), interval(0.0), frame_id("base_link"), latch(false)
101  {
102  // update potentially remapped topic name for later logging
104  }
105 
107  file_name = get_param("~file_name", file_name);
108  interval = get_param("~interval", interval);
109  frame_id = get_param("~frame_id", frame_id);
110  latch = get_param("~latch", latch);
111  }
112 
113  void parse_cmdline_args(int argc, char** argv) {
114  if (argc > 1) {
115  file_name = argv[1];
116  }
117  if (argc > 2) {
118  std::stringstream str(argv[2]);
119  double x;
120  if (str >> x)
121  interval = x;
122  }
123  }
124 
126  if (file_name.empty()) {
127  ROS_ERROR_STREAM("Can't load pointcloud: no file name provided");
128  return false;
129  }
130  else if (pcl::io::loadPCDFile(file_name, cloud) < 0) {
131  ROS_ERROR_STREAM("Failed to parse pointcloud from file ('" << file_name << "')");
132  return false;
133  }
134  // success: set frame_id appropriately
135  cloud.header.frame_id = frame_id;
136  return true;
137  }
138 
139  void init_run() {
140  // init publisher
141  pub = nh.advertise<sensor_msgs::PointCloud2>(cloud_topic, 1, latch);
142  // treat publishing once as a special case to interval publishing
143  bool oneshot = interval <= 0;
146  this,
147  oneshot);
148  }
149 
151  ROS_INFO_STREAM("Recognized the following parameters");
152  ROS_INFO_STREAM(" * file_name: " << file_name);
153  ROS_INFO_STREAM(" * interval: " << interval);
154  ROS_INFO_STREAM(" * frame_id: " << frame_id);
155  ROS_INFO_STREAM(" * topic_name: " << cloud_topic);
156  ROS_INFO_STREAM(" * latch: " << std::boolalpha << latch);
157  }
158 
160  ROS_INFO_STREAM("Loaded pointcloud with the following stats");
161  ROS_INFO_STREAM(" * number of points: " << cloud.width * cloud.height);
162  ROS_INFO_STREAM(" * total size [bytes]: " << cloud.data.size());
163  ROS_INFO_STREAM(" * channel names: " << pcl::getFieldsList(cloud));
164  }
165 };
166 
167 int main (int argc, char** argv) {
168  // init ROS
169  ros::init(argc, argv, "pcd_to_pointcloud");
170  // set up node
171  pcd_to_pointcloud node;
172  // initializes from ROS parameters
173  node.parse_ros_params();
174  // also allow config to be provided via command line args
175  // the latter take precedence
176  node.parse_cmdline_args(argc, argv);
177  // print info about effective configuration settings
178  node.print_config_info();
179  // try to load pointcloud from file
180  if (!node.try_load_pointcloud()) {
181  return -1;
182  }
183  // print info about pointcloud
184  node.print_data_info();
185  // initialize run
186  node.init_run();
187  // blocking call to process callbacks etc
188  ros::spin();
189 }
ros::Publisher
ROS_ERROR_STREAM
#define ROS_ERROR_STREAM(args)
pcl::getFieldsList
std::string getFieldsList(const sensor_msgs::PointCloud2 &cloud)
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
ros.h
pcd_to_pointcloud::pcd_to_pointcloud
pcd_to_pointcloud()
Definition: pcd_to_pointcloud.cpp:99
pcd_to_pointcloud
Definition: pcd_to_pointcloud.cpp:61
pcd_to_pointcloud::parse_ros_params
void parse_ros_params()
Definition: pcd_to_pointcloud.cpp:106
ROS_DEBUG_STREAM_ONCE
#define ROS_DEBUG_STREAM_ONCE(args)
pcd_to_pointcloud::publish
void publish()
Definition: pcd_to_pointcloud.cpp:79
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
pcd_to_pointcloud::pub
ros::Publisher pub
Definition: pcd_to_pointcloud.cpp:75
pcd_to_pointcloud::interval
double interval
Definition: pcd_to_pointcloud.cpp:68
ros::NodeHandle::resolveName
std::string resolveName(const std::string &name, bool remap=true) const
ROS_DEBUG
#define ROS_DEBUG(...)
pcd_to_pointcloud::latch
bool latch
Definition: pcd_to_pointcloud.cpp:72
pcd_to_pointcloud::parse_cmdline_args
void parse_cmdline_args(int argc, char **argv)
Definition: pcd_to_pointcloud.cpp:113
pcd_to_pointcloud::cloud
sensor_msgs::PointCloud2 cloud
Definition: pcd_to_pointcloud.cpp:74
get_param
T get_param(std::string const &name, T default_value)
Definition: pcd_to_pointcloud.cpp:55
pcd_to_pointcloud::nh
ros::NodeHandle nh
Definition: pcd_to_pointcloud.cpp:62
pcl::io::loadPCDFile
int loadPCDFile(const std::string &file_name, sensor_msgs::PointCloud2 &cloud)
ros::TimerEvent
ROS_INFO_STREAM
#define ROS_INFO_STREAM(args)
default_value
def default_value(type_)
pcd_to_pointcloud::timer_callback
void timer_callback(ros::TimerEvent const &)
Definition: pcd_to_pointcloud.cpp:93
pcd_to_pointcloud::timer
ros::Timer timer
Definition: pcd_to_pointcloud.cpp:77
pcd_to_pointcloud::print_data_info
void print_data_info()
Definition: pcd_to_pointcloud.cpp:159
pcd_to_pointcloud::frame_id
std::string frame_id
Definition: pcd_to_pointcloud.cpp:70
ros::spin
ROSCPP_DECL void spin()
ros::Publisher::getNumSubscribers
uint32_t getNumSubscribers() const
pcd_to_pointcloud::init_run
void init_run()
Definition: pcd_to_pointcloud.cpp:139
pcd_to_pointcloud::print_config_info
void print_config_info()
Definition: pcd_to_pointcloud.cpp:150
ros::NodeHandle::createTimer
Timer createTimer(Duration period, const TimerCallback &callback, bool oneshot=false, bool autostart=true) const
pcd_to_pointcloud::cloud_topic
std::string cloud_topic
Definition: pcd_to_pointcloud.cpp:64
ros::Duration
ros::Timer
main
int main(int argc, char **argv)
Definition: pcd_to_pointcloud.cpp:167
pcd_to_pointcloud::file_name
std::string file_name
Definition: pcd_to_pointcloud.cpp:66
ros::NodeHandle
pcd_to_pointcloud::try_load_pointcloud
bool try_load_pointcloud()
Definition: pcd_to_pointcloud.cpp:125
ros::Time::now
static Time now()
pcl_conversions.h


pcl_ros
Author(s): Open Perception, Julius Kammerl , William Woodall
autogenerated on Fri Jul 12 2024 02:54:40