spin_laser_snapshotter.cpp
Go to the documentation of this file.
1 // -*- mode: c++ -*-
2 /*********************************************************************
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2014, JSK Lab
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/o2r other materials provided
17  * with the distribution.
18  * * Neither the name of the Willow Garage nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *********************************************************************/
35 
36 #include <ros/ros.h>
37 
38 // Services
39 #include "laser_assembler/AssembleScans2.h"
40 
41 // Messages
42 #include "sensor_msgs/PointCloud2.h"
43 #include "sensor_msgs/JointState.h"
44 
46 #include <tf/transform_listener.h>
47 /***
48  * This uses the point_cloud_assembler's build_cloud service call to grab all the scans/clouds between two tilt-laser shutters
49  * params
50  * * "~target_frame_id" (string) - This is the frame that the scanned data transformed into. The
51  * output clouds are also published in this frame.
52  * * "~num_skips" (int) - If set to N>0, then the snapshotter will skip N signals before
53  * requesting a new snapshot. This will make the snapshots be N times
54  * larger. Default 0 - no skipping.
55  */
56 
58 {
59 
61 {
62 
63 public:
68 
70  double prev_angle_;
71 
76  double rate_;
77  std::string fixed_frame_;
78  std::string spindle_frame_;
79  std::string motor_frame_;
82  SpinLaserSnapshotter() : private_ns_("~")
83  {
84  prev_signal_.fromNSec(0);
85 
86  pub_ = n_.advertise<sensor_msgs::PointCloud2> ("full_cloud2", 1);
87 
88  private_ns_.param("num_skips", num_skips_, 0);
89  num_skips_left_=num_skips_;
90 
91  prev_angle_ = -1;
92  first_time_ = true;
93  private_ns_.param("negative_direction", negative_direction_, false);
94  ROS_INFO_STREAM("negative_direction: " << negative_direction_);
95  bool use_tf;
96  private_ns_.param("use_tf", use_tf, false);
97  if (!use_tf) {
98  sub_ = n_.subscribe("joint_states", 40, &SpinLaserSnapshotter::scannerSignalCallback, this);
99  }
100  else {
101  listener_ = new tf::TransformListener();
102  private_ns_.param("tf_polling_rate", rate_, 30.0);
103  private_ns_.param("spindle_frame", spindle_frame_, std::string("multisense/spindle"));
104  private_ns_.param("motor_frame", motor_frame_, std::string("multisense/motor"));
105  timer_ = private_ns_.createTimer(
106  ros::Duration(1.0 / rate_), boost::bind(
108  }
109  }
110 
112  {
113 
114  }
115 
116  void timerCallback(const ros::TimerEvent& event)
117  {
118  // only if it is possible to transform from motor_frame_ -> spindle_frame_
119  if (listener_->waitForTransform(motor_frame_, spindle_frame_, event.current_real,
120  ros::Duration(1 / rate_))) {
121  tf::StampedTransform transform;
122  listener_->lookupTransform(spindle_frame_, motor_frame_, event.current_real, transform);
123  // compute quaternion into eigen
124  Eigen::Affine3d t;
125  tf::transformTFToEigen(transform, t);
126  double yaw = atan2(t(1,0), t(0,0));
127  sensor_msgs::JointState js;
128  js.header.stamp = transform.stamp_;
129  js.position.push_back(yaw);
130  const sensor_msgs::JointState js_const (js);
131  scannerSignalCallback(boost::make_shared<sensor_msgs::JointState>(js_const));
132  }
133  }
134 
135  void scannerSignalCallback(const sensor_msgs::JointStateConstPtr& js)
136  {
137  double theta = js->position[0];
138  if (negative_direction_) {
139  theta = - theta;
140  }
141  double ang = fmod(theta, 2 * M_PI);
142 
143  // ROS_DEBUG("ang = %lf, prev_angle = %lf, %lf", ang, prev_angle_, prev_signal_.toSec());
144 
145  if ( prev_angle_ < 0 ) {
146  prev_angle_ = ang;
147  return;
148  }
149  if ((ang - prev_angle_) >= - M_PI) {
150  prev_angle_ = ang;
151  return;
152  }
153 
154  if (prev_signal_.toSec() == 0.0) {
155  first_time_ = true;
156  }
157 
158  ros::Time stmp = js->header.stamp;
159  if (first_time_)
160  {
161  prev_signal_ = stmp;
162  first_time_ = false;
163  }
164  else
165  {
166  if (num_skips_ > 0)
167  {
168  if (num_skips_left_ > 0)
169  {
170  num_skips_left_ -= 1;
171  return;
172  }
173  else
174  {
175  num_skips_left_ = num_skips_;
176  }
177  }
178 
179  laser_assembler::AssembleScans2::Request req;
180  laser_assembler::AssembleScans2::Response res;
181 
182  req.begin = prev_signal_;
183  req.end = stmp;
184  if (!ros::service::call("assemble_scans2", req, res))
185  ROS_ERROR("Failed to call service on point cloud assembler or laser scan assembler.");
186 
187  pub_.publish(res.cloud);
188  ROS_DEBUG("Snapshotter::Published Cloud size=%u", res.cloud.width * res.cloud.height);
189 
190  prev_signal_ = stmp;
191  prev_angle_ = -1;
192  }
193  }
194 };
195 }
196 
197 using namespace spin_laser_snapshotter;
198 
199 int main(int argc, char **argv)
200 {
201  ros::init(argc, argv, "spin_laser_snapshotter");
202  SpinLaserSnapshotter snapshotter ;
203  ros::spin();
204  return 0;
205 }
void publish(const boost::shared_ptr< M > &message) const
void transformTFToEigen(const tf::Transform &t, Eigen::Affine3d &e)
Time & fromNSec(uint64_t t)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
bool call(const std::string &service_name, MReq &req, MRes &res)
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
void scannerSignalCallback(const sensor_msgs::JointStateConstPtr &js)
ROSCPP_DECL void spin(Spinner &spinner)
bool waitForTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, const ros::Duration &timeout, const ros::Duration &polling_sleep_duration=ros::Duration(0.01), std::string *error_msg=NULL) const
bool param(const std::string &param_name, T &param_val, const T &default_val) const
Timer createTimer(Rate r, Handler h, Obj o, bool oneshot=false, bool autostart=true) const
void timerCallback(const ros::TimerEvent &event)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
void lookupTransform(const std::string &target_frame, const std::string &source_frame, const ros::Time &time, StampedTransform &transform) const
#define ROS_INFO_STREAM(args)
INLINE Rall1d< T, V, S > atan2(const Rall1d< T, V, S > &y, const Rall1d< T, V, S > &x)
#define ROS_ERROR(...)
int main(int argc, char **argv)
#define ROS_DEBUG(...)


jsk_tilt_laser
Author(s): YoheiKakiuchi
autogenerated on Tue Feb 6 2018 03:45:14