bag_io.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: bag_io.cpp 34896 2010-12-19 06:21:42Z rusu $
35  *
36  */
37 
39 #include <ros/node_handle.h>
40 #include "pcl_ros/io/bag_io.h"
41 
43 bool
44 pcl_ros::BAGReader::open (const std::string &file_name, const std::string &topic_name)
45 {
46  try
47  {
48  bag_.open (file_name, rosbag::bagmode::Read);
49  view_.addQuery (bag_, rosbag::TopicQuery (topic_name));
50 
51  if (view_.size () == 0)
52  return (false);
53 
54  it_ = view_.begin ();
55  }
56  catch (rosbag::BagException &e)
57  {
58  return (false);
59  }
60  return (true);
61 }
62 
64 void
66 {
68  pnh_.reset (new ros::NodeHandle (getMTPrivateNodeHandle ()));
69  // ---[ Mandatory parameters
70  if (!pnh_->getParam ("file_name", file_name_))
71  {
72  NODELET_ERROR ("[onInit] Need a 'file_name' parameter to be set before continuing!");
73  return;
74  }
75  if (!pnh_->getParam ("topic_name", topic_name_))
76  {
77  NODELET_ERROR ("[onInit] Need a 'topic_name' parameter to be set before continuing!");
78  return;
79  }
80  // ---[ Optional parameters
81  int max_queue_size = 1;
82  pnh_->getParam ("publish_rate", publish_rate_);
83  pnh_->getParam ("max_queue_size", max_queue_size);
84 
85  ros::Publisher pub_output = pnh_->advertise<sensor_msgs::PointCloud2> ("output", max_queue_size);
86 
87  NODELET_DEBUG ("[onInit] Nodelet successfully created with the following parameters:\n"
88  " - file_name : %s\n"
89  " - topic_name : %s",
90  file_name_.c_str (), topic_name_.c_str ());
91 
92  if (!open (file_name_, topic_name_))
93  return;
94  PointCloud output;
95  output_ = boost::make_shared<PointCloud> (output);
96  output_->header.stamp = ros::Time::now ();
97 
98  // Continous publishing enabled?
99  while (pnh_->ok ())
100  {
101  PointCloudConstPtr cloud = getNextCloud ();
102  NODELET_DEBUG ("Publishing data (%d points) on topic %s in frame %s.", output_->width * output_->height, pnh_->resolveName ("output").c_str (), output_->header.frame_id.c_str ());
103  output_->header.stamp = ros::Time::now ();
104 
105  pub_output.publish (output_);
106 
107  ros::Duration (publish_rate_).sleep ();
108  ros::spinOnce ();
109  }
110 }
111 
114 
pcl_ros::BAGReader::PointCloudConstPtr
PointCloud::ConstPtr PointCloudConstPtr
Definition: bag_io.h:58
node_handle.h
NODELET_ERROR
#define NODELET_ERROR(...)
ros::Publisher
rosbag::View::size
uint32_t size()
boost::shared_ptr< ros::NodeHandle >
pcl_ros::BAGReader::PointCloud
sensor_msgs::PointCloud2 PointCloud
Definition: bag_io.h:56
pcl_ros::BAGReader
BAG PointCloud file format reader.
Definition: bag_io.h:53
pcl_ros::BAGReader::onInit
virtual void onInit()
Nodelet initialization routine.
Definition: bag_io.cpp:65
ros::spinOnce
ROSCPP_DECL void spinOnce()
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
rosbag::bagmode::Read
Read
pcl_ros::BAGReader::view_
rosbag::View view_
The BAG view object.
Definition: bag_io.h:109
rosbag::BagException
PLUGINLIB_EXPORT_CLASS
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
pcl_ros::BAGReader::it_
rosbag::View::iterator it_
The BAG view iterator object.
Definition: bag_io.h:112
rosbag::TopicQuery
rosbag::View::addQuery
void addQuery(Bag const &bag, boost::function< bool(ConnectionInfo const *)> query, ros::Time const &start_time=ros::TIME_MIN, ros::Time const &end_time=ros::TIME_MAX)
bag_io.h
nodelet::Nodelet
pcl_ros::BAGReader::open
bool open(const std::string &file_name, const std::string &topic_name)
Open a BAG file for reading and select a specified topic.
Definition: bag_io.cpp:44
BAGReader
pcl_ros::BAGReader BAGReader
Definition: bag_io.cpp:112
class_list_macros.hpp
pcl_ros::BAGReader::bag_
rosbag::Bag bag_
The BAG object.
Definition: bag_io.h:106
ros::Duration::sleep
bool sleep() const
rosbag::Bag::open
void open(std::string const &filename, uint32_t mode=bagmode::Read)
rosbag::View::begin
iterator begin()
ros::Duration
ros::NodeHandle
NODELET_DEBUG
#define NODELET_DEBUG(...)
ros::Time::now
static Time now()


pcl_ros
Author(s): Open Perception, Julius Kammerl , William Woodall
autogenerated on Sat Feb 18 2023 03:54:54