snapshotter_action.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2009, Willow Garage, Inc.
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the Willow Garage, Inc. nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
30 #include <ros/ros.h>
31 
32 // Action Interface
34 #include <pr2_tilt_laser_interface/GetSnapshotAction.h>
35 
36 // Controller Interface
37 #include <pr2_msgs/SetLaserTrajCmd.h>
38 
39 // Laser Processing
40 #include <sensor_msgs/LaserScan.h>
42 #include <pcl_ros/transforms.h>
44 
45 #include <tf/transform_listener.h>
46 #include "tf/message_filter.h"
48 #include <pcl/io/io.h>
49 
50 void appendCloud(sensor_msgs::PointCloud2& dest, const sensor_msgs::PointCloud2& src)
51 {
52  // TODO: Add error/consistency checking here
53  dest.height += 1;
54 
55  size_t start = dest.data.size ();
56 
57  if (start == 0)
58  {
59  dest = src;
60  return;
61  }
62 
63  dest.data.resize (start + src.data.size ());
64  memcpy (&dest.data[start], &src.data[0], src.data.size ());
65 
66  // Get the time index field offset
67  int time_index = src.fields[pcl::getFieldIndex (dest, "timestamp")].offset;
68  float time_offset = src.header.stamp.toSec () - dest.header.stamp.toSec ();
69  float* time_ptr;
70  for (size_t i = 0; i < src.width * src.height; ++i)
71  {
72  time_ptr = (float*) &dest.data[start + i * src.point_step + time_index];
73  *time_ptr += time_offset;
74  }
75 }
76 
77 using namespace pr2_tilt_laser_interface;
78 
79 namespace SnapshotStates
80 {
82  {
84  IDLE = 2
85  };
86 }
88 
90 
92 {
93 public:
94  Snapshotter();
95 
96  void startScan(double move_to_start_wait_time=1.0);
97 
98  void scanCallback(const sensor_msgs::LaserScanConstPtr& scan);
99 
100  // Action Interface
101  void goalCallback(SnapshotActionServer::GoalHandle gh);
102  void cancelCallback(SnapshotActionServer::GoalHandle gh);
103 
104 private:
107 
110 
111  boost::mutex state_mutex_;
116  GetSnapshotResult snapshot_result_;
117  GetSnapshotFeedback snapshot_feedback_;
118 
120  GetSnapshotGoal goal_;
121 
123  std::string fixed_frame_;
124  boost::scoped_ptr<tf::MessageFilter<sensor_msgs::LaserScan> > tf_filter_;
125 
126 };
127 
129  as_(nh_, "get_laser_snapshot", false),
130  state_(SnapshotStates::IDLE),
131  tf_(nh_)
132 {
133  as_.registerGoalCallback( boost::bind(&Snapshotter::goalCallback, this, _1) );
134  as_.registerCancelCallback( boost::bind(&Snapshotter::cancelCallback, this, _1) );
135 
136  // Initialize interface to the controller
137  // TODO: Make this into an action interface, once the controller supports it
138  laser_controller_sc_ = nh_.serviceClient<pr2_msgs::SetLaserTrajCmd>("laser_tilt_controller/set_traj_cmd");
139 
140  // Grab the fixed frame off the parameter server
141  ros::NodeHandle private_ns_("~");
142  if (!private_ns_.getParam("fixed_frame", fixed_frame_))
143  ROS_FATAL("Need to set parameter ~fixed_frame");
144  ROS_DEBUG("Using fixed frame [%s]", fixed_frame_.c_str());
145 
146  // Set up the tf filter
147  scan_sub_.subscribe(nh_, "tilt_scan", 10);
149  tf_filter_->setTolerance(ros::Duration(0.025));
150  tf_filter_->registerCallback( boost::bind(&Snapshotter::scanCallback, this, _1) );
151 
152  // Start the action server
153  as_.start();
154 }
155 
156 void Snapshotter::scanCallback(const sensor_msgs::LaserScanConstPtr& scan)
157 {
158  boost::mutex::scoped_lock lock(state_mutex_);
159 
161  return;
162 
163  sensor_msgs::PointCloud2& cloud = (goal_.continuous ? snapshot_feedback_.cloud : snapshot_result_.cloud);
164 
166  {
167  if (scan->header.stamp < interval_start_)
168  {
169  ROS_DEBUG("Waiting to get to the start of the interval");
170  // Can't do anything since we haven't gotten to our interval yet
171  return;
172  }
173  else if (scan->header.stamp < interval_end_)
174  {
175  // Process Scans
176  ROS_DEBUG("In the actual interval");
177  sensor_msgs::PointCloud2 cur_cloud_tf;
178 
179  if (!goal_.hi_fidelity)
180  {
181  sensor_msgs::PointCloud2 cur_cloud;
182  lg_.projectLaser (*scan, cur_cloud);
183  tf::StampedTransform net_transform;
184  tf_.lookupTransform (fixed_frame_, cur_cloud.header.frame_id, cur_cloud.header.stamp, net_transform);
185  pcl_ros::transformPointCloud (fixed_frame_, net_transform, cur_cloud, cur_cloud_tf);
186  }
187  else
188  {
189  lg_.transformLaserScanToPointCloud (fixed_frame_, *scan, cur_cloud_tf, tf_);
190  }
191  appendCloud (cloud, cur_cloud_tf);
192  }
193  else
194  {
195  ROS_DEBUG ("Bundling everything up and publishing cloud with %u points", cloud.width * cloud.width);
196 
198 
199  if (goal_.continuous)
200  {
201  // TODO: Send out msg and start next scan
203  std::swap(goal_.start_angle, goal_.end_angle);
204  startScan(0.1);
205  }
206  else
207  {
209  }
210  cloud.data.clear ();
211  }
212  }
213  else
214  ROS_ERROR("In an unknown state. This is a programming error");
215 
216 }
217 
219 {
220  boost::mutex::scoped_lock lock(state_mutex_);
221 
222  // Preemption Logic
224  {
227  }
228 
229  current_gh_ = gh;
231 
233 
234  startScan();
235 }
236 
237 void Snapshotter::startScan(double move_to_start_wait_time)
238 {
239  //boost::mutex::scoped_lock lock(state_mutex_);
240 
241  // Build the service request for the tilt laser controller
242 
243  pr2_msgs::LaserTrajCmd cmd;
244 
245  cmd.profile = "linear";
246  cmd.position.resize(4);
247  cmd.position[0] = goal_.start_angle;
248  cmd.position[1] = goal_.start_angle;
249  cmd.position[2] = goal_.end_angle;
250  cmd.position[3] = (goal_.continuous ? goal_.end_angle : goal_.start_angle);
251 
252  if (goal_.speed==0.0)
253  {
254  ROS_ERROR("Scan speed is set to zero -> aborting!\n");
255  return;
256  }
257 
258  ros::Duration scan_duration( (goal_.start_angle - goal_.end_angle)/goal_.speed );
259  if (scan_duration.toSec() < 0.0)
260  scan_duration = -scan_duration;
261 
262  ros::Duration wait_time(move_to_start_wait_time);
263  cmd.time_from_start.resize(4);
264  cmd.time_from_start[0] = ros::Duration(0.0);
265  cmd.time_from_start[1] = wait_time;
266  cmd.time_from_start[2] = wait_time + scan_duration;
267  cmd.time_from_start[3] = wait_time + scan_duration + scan_duration;
268  cmd.max_velocity = 0;
269  cmd.max_acceleration= 0;
270 
271  pr2_msgs::SetLaserTrajCmd laser_srv_cmd;
272  laser_srv_cmd.request.command = cmd;
273 
274  laser_controller_sc_.call(laser_srv_cmd);
275 
276  // Determine the interval that we care about, based on the service response
277  interval_start_ = laser_srv_cmd.response.start_time + cmd.time_from_start[1];
278  interval_end_ = laser_srv_cmd.response.start_time + cmd.time_from_start[2];
279 
280  // Load the new goal
281  assert(state_ == SnapshotStates::IDLE);
283 
284  snapshot_feedback_.cloud.data.clear();
285  snapshot_result_.cloud.data.clear();
286 }
287 
289 {
290  boost::mutex::scoped_lock lock(state_mutex_);
291 
292  // See if our current goal is the one that needs to be cancelled
293  if (current_gh_ != gh)
294  {
295  ROS_DEBUG("Got a cancel request for some other goal. Ignoring it");
296  return;
297  }
300 }
301 
302 //void printUsage(const char* progName)
303 //{
304  //std::cout << "\n\nUsage: "<<progName<<" [options]\n\n"
305  //<< "Options:\n"
306  //<< "-------------------------------------------\n"
307  //<< "-c Continuous - after receiving one action request, continue doing 3D scans all the time.\n"
308  //<< "-h this help\n"
309  //<< "\n\n";
310 //}
311 
312 int main(int argc, char** argv)
313 {
315  //bool continuous_mode = false;
316  //for (char c; (c = getopt(argc, argv, "ch")) != -1; ) {
317  //switch (c) {
318  //case 'c':
319  //continuous_mode = true;
320  //std::cout << "Using continuous mode.\n";
321  //break;
322  //case 'h':
323  //printUsage(argv[0]);
324  //exit(0);
325  //}
326  //}
327 
328  ros::init(argc, argv, "laser_snapshotter");
329  Snapshotter snapshotter;
330  ros::spin();
331 }
void projectLaser(const sensor_msgs::LaserScan &scan_in, sensor_msgs::PointCloud &cloud_out, double range_cutoff=-1.0, int channel_options=channel_option::Default)
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
void publishFeedback(const Feedback &feedback)
#define ROS_FATAL(...)
SnapshotActionServer as_
message_filters::Subscriber< sensor_msgs::LaserScan > scan_sub_
void cancelCallback(SnapshotActionServer::GoalHandle gh)
ServerGoalHandle< GetSnapshotAction > GoalHandle
boost::mutex state_mutex_
string cmd
int main(int argc, char **argv)
laser_geometry::LaserProjection lg_
ros::Time interval_start_
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
bool call(MReq &req, MRes &res)
boost::shared_ptr< const Goal > getGoal() const
GetSnapshotResult snapshot_result_
void setCanceled(const Result &result=Result(), const std::string &text=std::string(""))
ROSCPP_DECL void spin(Spinner &spinner)
SnapshotStates::SnapshotState SnapshotState
void setAccepted(const std::string &text=std::string(""))
void registerGoalCallback(boost::function< void(GoalHandle)> cb)
std::string fixed_frame_
void startScan(double move_to_start_wait_time=1.0)
void setSucceeded(const Result &result=Result(), const std::string &text=std::string(""))
void goalCallback(SnapshotActionServer::GoalHandle gh)
GetSnapshotGoal goal_
void scanCallback(const sensor_msgs::LaserScanConstPtr &scan)
ros::Time interval_end_
SnapshotActionServer::GoalHandle current_gh_
void lookupTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, StampedTransform &transform) const
void appendCloud(sensor_msgs::PointCloud2 &dest, const sensor_msgs::PointCloud2 &src)
void registerCancelCallback(boost::function< void(GoalHandle)> cb)
ros::ServiceClient laser_controller_sc_
void subscribe(ros::NodeHandle &nh, const std::string &topic, uint32_t queue_size, const ros::TransportHints &transport_hints=ros::TransportHints(), ros::CallbackQueueInterface *callback_queue=0)
void transformPointCloud(const pcl::PointCloud< PointT > &cloud_in, pcl::PointCloud< PointT > &cloud_out, const tf::Transform &transform)
SnapshotState state_
void transformLaserScanToPointCloud(const std::string &target_frame, const sensor_msgs::LaserScan &scan_in, sensor_msgs::PointCloud &cloud_out, tf::Transformer &tf, double range_cutoff, int channel_options=channel_option::Default)
boost::scoped_ptr< tf::MessageFilter< sensor_msgs::LaserScan > > tf_filter_
#define ROS_ERROR(...)
actionlib::ActionServer< GetSnapshotAction > SnapshotActionServer
int getFieldIndex(const sensor_msgs::PointCloud2 &cloud, const std::string &field_name)
GetSnapshotFeedback snapshot_feedback_
ros::NodeHandle nh_
tf::TransformListener tf_
#define ROS_DEBUG(...)


pr2_tilt_laser_interface
Author(s): Radu Rusu, Wim Meeusen, Vijay Pradeep
autogenerated on Fri Jun 7 2019 22:06:44