periodic_snapshotter.cpp
Go to the documentation of this file.
1 /*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2008, 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 the Willow Garage 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 
35 #include <cstdio>
36 #include <ros/ros.h>
37 
38 // Services
39 #include "laser_assembler/AssembleScans.h"
40 
41 // Messages
42 #include "sensor_msgs/PointCloud.h"
43 
44 
45 /***
46  * This a simple test app that requests a point cloud from the
47  * point_cloud_assembler every 4 seconds, and then publishes the
48  * resulting data
49  */
50 namespace laser_assembler
51 {
52 
54 {
55 
56 public:
57 
59  {
60  // Create a publisher for the clouds that we assemble
61  pub_ = n_.advertise<sensor_msgs::PointCloud> ("assembled_cloud", 1);
62 
63  // Create the service client for calling the assembler
64  client_ = n_.serviceClient<AssembleScans>("assemble_scans");
65 
66  // Start the timer that will trigger the processing loop (timerCallback)
68 
69  // Need to track if we've called the timerCallback at least once
70  first_time_ = true;
71  }
72 
73  void timerCallback(const ros::TimerEvent& e)
74  {
75 
76  // We don't want to build a cloud the first callback, since we we
77  // don't have a start and end time yet
78  if (first_time_)
79  {
80  first_time_ = false;
81  return;
82  }
83 
84  // Populate our service request based on our timer callback times
85  AssembleScans srv;
86  srv.request.begin = e.last_real;
87  srv.request.end = e.current_real;
88 
89  // Make the service call
90  if (client_.call(srv))
91  {
92  ROS_INFO("Published Cloud with %u points", (uint32_t)(srv.response.cloud.points.size())) ;
93  pub_.publish(srv.response.cloud);
94  }
95  else
96  {
97  ROS_ERROR("Error making service call\n") ;
98  }
99  }
100 
101 private:
106  bool first_time_;
107 } ;
108 
109 }
110 
111 using namespace laser_assembler ;
112 
113 int main(int argc, char **argv)
114 {
115  ros::init(argc, argv, "periodic_snapshotter");
116  ros::NodeHandle n;
117  ROS_INFO("Waiting for [build_cloud] to be advertised");
118  ros::service::waitForService("build_cloud");
119  ROS_INFO("Found build_cloud! Starting the snapshotter");
120  PeriodicSnapshotter snapshotter;
121  ros::spin();
122  return 0;
123 }
ros::Publisher
laser_assembler::PeriodicSnapshotter::n_
ros::NodeHandle n_
Definition: periodic_snapshotter.cpp:174
laser_assembler::PeriodicSnapshotter::pub_
ros::Publisher pub_
Definition: periodic_snapshotter.cpp:175
ros::init
ROSCPP_DECL void init(const M_string &remappings, const std::string &name, uint32_t options=0)
ros::TimerEvent::last_real
Time last_real
laser_assembler::PeriodicSnapshotter::PeriodicSnapshotter
PeriodicSnapshotter()
Definition: periodic_snapshotter.cpp:130
ros.h
laser_assembler::PeriodicSnapshotter::client_
ros::ServiceClient client_
Definition: periodic_snapshotter.cpp:176
ros::NodeHandle::serviceClient
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
laser_assembler::PeriodicSnapshotter::timer_
ros::Timer timer_
Definition: periodic_snapshotter.cpp:177
ros::NodeHandle::advertise
Publisher advertise(AdvertiseOptions &ops)
ros::ServiceClient
laser_assembler::PeriodicSnapshotter::timerCallback
void timerCallback(const ros::TimerEvent &e)
Definition: periodic_snapshotter.cpp:145
ros::TimerEvent
ros::TimerEvent::current_real
Time current_real
laser_assembler::PeriodicSnapshotter::first_time_
bool first_time_
Definition: periodic_snapshotter.cpp:178
laser_assembler
Definition: periodic_snapshotter.cpp:50
ROS_ERROR
#define ROS_ERROR(...)
ros::ServiceClient::call
bool call(const MReq &req, MRes &resp, const std::string &service_md5sum)
ros::service::waitForService
ROSCPP_DECL bool waitForService(const std::string &service_name, int32_t timeout)
ros::spin
ROSCPP_DECL void spin()
main
int main(int argc, char **argv)
Definition: periodic_snapshotter.cpp:113
ROS_INFO
#define ROS_INFO(...)
laser_assembler::PeriodicSnapshotter
Definition: periodic_snapshotter.cpp:89
ros::NodeHandle::createTimer
Timer createTimer(Duration period, const TimerCallback &callback, bool oneshot=false, bool autostart=true) const
ros::Duration
ros::Timer
ros::NodeHandle


laser_assembler
Author(s): Vijay Pradeep
autogenerated on Sat Aug 10 2024 02:10:39