rotunit_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 <math.h>
37 #include <ros/ros.h>
38 #include <sensor_msgs/JointState.h>
39 
40 // Services
41 #include "laser_assembler/AssembleScans2.h"
42 
43 // Messages
44 #include "sensor_msgs/PointCloud2.h"
45 
46 /***
47  * This a simple test app that requests a point cloud from the
48  * point_cloud_assembler every 4 seconds, and then publishes the
49  * resulting data
50  */
51 namespace laser_assembler
52 {
53 
55 {
56 
57 public:
58 
60  {
61  // Create a publisher for the clouds that we assemble
62  pub_ = n_.advertise<sensor_msgs::PointCloud2> ("assembled_cloud", 1);
63 
64  sub_ = n_.subscribe("joint_states", 1000, &PeriodicSnapshotter::rotCallback, this);
65 
66  // Create the service client for calling the assembler
67  client_ = n_.serviceClient<AssembleScans2>("assemble_scans2");
68 
69  first_time_ = true;
70  arm_ = false;
71  }
72 
76  int getIndex(const sensor_msgs::JointState::ConstPtr& e)
77  {
78  for (size_t i = 0; i < e->name.size(); ++i)
79  {
80  if (e->name[i] == "laser_rot_joint")
81  return i;
82  }
83  return -1;
84  }
85 
86  void rotCallback(const sensor_msgs::JointState::ConstPtr& e)
87  {
88 
89  if(first_time_) {
90  last_time_ = e->header.stamp;
91  first_time_ = false;
92  return;
93  }
94 
95  int index = getIndex(e);
96  if (index < 0)
97  return;
98 
99  double position = fmod(e->position[index], 2 * M_PI);
100 
101  if (!arm_ && position > 3) {
102  arm_ = true;
103  return;
104  }
105 
106  if(arm_ && position > 0 && position < 1) {
107 
108  // Populate our service request based on our timer callback times
109  AssembleScans2 srv;
110  srv.request.begin = last_time_;
111  srv.request.end = e->header.stamp;
112 
113  // Make the service call
114  if (client_.call(srv))
115  {
116  ROS_INFO("Published Cloud with %u points", srv.response.cloud.width * srv.response.cloud.height) ;
117  pub_.publish(srv.response.cloud);
118  }
119  else
120  {
121  ROS_ERROR("Error making service call\n") ;
122  }
123 
124  arm_ = false;
125  last_time_ = e->header.stamp;
126  }
127  }
128 
129 private:
132  ros::Subscriber sub_;
134  bool first_time_;
135  bool arm_;
136  ros::Time last_time_;
137 } ;
138 
139 }
140 
141 using namespace laser_assembler ;
142 
143 int main(int argc, char **argv)
144 {
145  ros::init(argc, argv, "rotunit_snapshotter");
146  ros::NodeHandle n;
147  ROS_INFO("Waiting for [assemble_scans2] to be advertised");
148  ros::service::waitForService("assemble_scans2");
149  ROS_INFO("Found assemble_scans2! Starting the snapshotter");
150  PeriodicSnapshotter snapshotter;
151  ros::spin();
152  return 0;
153 }
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
void publish(const boost::shared_ptr< M > &message) const
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
bool call(MReq &req, MRes &res)
ROSCPP_DECL void spin(Spinner &spinner)
#define ROS_INFO(...)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
int main(int argc, char **argv)
#define ROS_ERROR(...)
ROSCPP_DECL bool waitForService(const std::string &service_name, int32_t timeout)


rotunit_snapshotter
Author(s): jspricke
autogenerated on Mon Jun 10 2019 15:49:19