tilt_laser_listener_nodelet.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 JSK Lab 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 #define BOOST_PARAMETER_MAX_ARITY 7
37 #include <laser_assembler/AssembleScans2.h>
40 
41 namespace jsk_pcl_ros
42 {
43  StampedJointAngle::StampedJointAngle(const std_msgs::Header& header_arg, const double& value):
44  header(header_arg), value_(value)
45  {
46 
47  }
48 
50  {
51  DiagnosticNodelet::onInit();
52  skip_counter_ = 0;
53  if (pnh_->hasParam("joint_name")) {
54  pnh_->getParam("joint_name", joint_name_);
55  }
56  else {
57  NODELET_ERROR("no ~joint_state is specified");
58  return;
59  }
60  pnh_->getParam("twist_frame_id", twist_frame_id_);
61  pnh_->param("overwrap_angle", overwrap_angle_, 0.0);
62  std::string laser_type;
63  bool subscribe_joint = true;
64  pnh_->param("clear_assembled_scans", clear_assembled_scans_, false);
65  pnh_->param("skip_number", skip_number_, 1);
66  pnh_->param("laser_type", laser_type, std::string("tilt_half_down"));
67  pnh_->param("max_queue_size", max_queue_size_, 100);
68  pnh_->param("publish_rate", publish_rate_, 1.0);
69  if (laser_type == "tilt_half_up") {
70  laser_type_ = TILT_HALF_UP;
71  }
72  else if (laser_type == "tilt_half_down") {
73  laser_type_ = TILT_HALF_DOWN;
74  }
75  else if (laser_type == "tilt") {
76  laser_type_ = TILT;
77  }
78  else if (laser_type == "infinite_spindle") {
79  laser_type_ = INFINITE_SPINDLE;
80  }
81  else if (laser_type == "infinite_spindle_half") {
82  laser_type_ = INFINITE_SPINDLE_HALF;
83  }
84  else if (laser_type == "periodic") {
85  laser_type_ = PERIODIC;
86  periodic_timer_ = pnh_->createTimer(ros::Duration(1/publish_rate_), &TiltLaserListener::timerCallback, this);
87  subscribe_joint = false;
88  }
89  else {
90  NODELET_ERROR("unknown ~laser_type: %s", laser_type.c_str());
91  return;
92  }
93  pnh_->param("not_use_laser_assembler_service", not_use_laser_assembler_service_, false);
94  pnh_->param("use_laser_assembler", use_laser_assembler_, false);
95  double vital_rate;
96  pnh_->param("vital_rate", vital_rate, 1.0);
97  cloud_vital_checker_.reset(
98  new jsk_topic_tools::VitalChecker(1 / vital_rate));
99  if (use_laser_assembler_) {
100  if (not_use_laser_assembler_service_) {
101  sub_cloud_
102  = pnh_->subscribe("input/cloud", max_queue_size_, &TiltLaserListener::cloudCallback, this);
103  }
104  else {
105  assemble_cloud_srv_
106  = pnh_->serviceClient<laser_assembler::AssembleScans2>("assemble_scans2");
107  }
108  cloud_pub_
109  = pnh_->advertise<sensor_msgs::PointCloud2>("output_cloud", 1);
110  }
111  twist_pub_ = pnh_->advertise<geometry_msgs::TwistStamped>("output_velocity", 1);
112  prev_angle_ = 0;
113  prev_velocity_ = 0;
114  start_time_ = ros::Time::now();
115  clear_cache_service_ = pnh_->advertiseService(
117  this);
118  trigger_pub_ = advertise<jsk_recognition_msgs::TimeRange>(*pnh_, "output", 1);
119  if(subscribe_joint) {
120  sub_ = pnh_->subscribe("input", max_queue_size_, &TiltLaserListener::jointCallback, this);
121  }
122 
123  onInitPostProcess();
124  }
125 
127  {
128  boost::mutex::scoped_lock lock(mutex_);
129  vital_checker_->poke();
130  publishTimeRange(e.current_real, e.last_real, e.current_real);
131  start_time_ = e.current_real; // not used??
132  }
133 
135  {
136 
137  }
138 
140  {
141 
142  }
143 
146  {
147  boost::mutex::scoped_lock lock(cloud_mutex_);
148  if (vital_checker_->isAlive()) {
149  if (not_use_laser_assembler_service_ &&
150  use_laser_assembler_) {
151  if (cloud_vital_checker_->isAlive()) {
152  stat.summary(diagnostic_msgs::DiagnosticStatus::OK,
153  getName() + " running");
154  }
155  else {
156  stat.summary(diagnostic_error_level_,
157  "~input/cloud is not activate");
158  }
159  stat.add("scan queue", cloud_buffer_.size());
160  }
161  else {
162  stat.summary(diagnostic_msgs::DiagnosticStatus::OK,
163  getName() + " running");
164  }
165 
166  }
167  else {
169  name_, vital_checker_, stat, diagnostic_error_level_);
170  }
171  }
172 
174  const sensor_msgs::PointCloud2::ConstPtr& msg)
175  {
176  boost::mutex::scoped_lock lock(cloud_mutex_);
177  cloud_vital_checker_->poke();
178  cloud_buffer_.push_back(msg);
179  }
180 
182  std_srvs::Empty::Request& req,
183  std_srvs::Empty::Response& res)
184  {
185  boost::mutex::scoped_lock lock(mutex_);
186  buffer_.clear();
187  return true;
188  }
189 
191  const std::vector<sensor_msgs::PointCloud2::ConstPtr>& target_clouds,
192  sensor_msgs::PointCloud2& output_cloud)
193  {
194  if (target_clouds.size() > 0) {
195  output_cloud.fields = target_clouds[0]->fields;
196  output_cloud.is_bigendian = target_clouds[0]->is_bigendian;
197  output_cloud.is_dense = true;
198  output_cloud.point_step = target_clouds[0]->point_step;
199  size_t point_num = 0;
200  size_t data_num = 0;
201  for (size_t i = 0; i < target_clouds.size(); i++) {
202  data_num += target_clouds[i]->row_step;
203  point_num += target_clouds[i]->width * target_clouds[i]->height;
204  }
205  output_cloud.data.reserve(data_num);
206  for (size_t i = 0; i < target_clouds.size(); i++) {
207  std::copy(target_clouds[i]->data.begin(),
208  target_clouds[i]->data.end(),
209  std::back_inserter(output_cloud.data));
210  }
211  output_cloud.header.frame_id = target_clouds[0]->header.frame_id;
212  output_cloud.width = point_num;
213  output_cloud.height = 1;
214  output_cloud.row_step = data_num;
215  }
216  else {
217  NODELET_WARN("target_clouds size is 0");
218  }
219  }
220 
222  const ros::Time& stamp,
223  const ros::Time& start,
224  const ros::Time& end)
225  {
226  jsk_recognition_msgs::TimeRange range;
227  range.header.stamp = stamp;
228  range.start = start;
229  range.end = end;
230  trigger_pub_.publish(range);
231 
232  // publish velocity
233  // only publish if twist_frame_id is not empty
234  if (!twist_frame_id_.empty()) {
235  // simply compute from the latest velocity
236  if (buffer_.size() >= 2) {
237  // at least, we need two joint angles to
238  // compute velocity
239  StampedJointAngle::Ptr latest = buffer_[buffer_.size() - 1];
240  StampedJointAngle::Ptr last_second = buffer_[buffer_.size() - 2];
241  double value_diff = latest->getValue() - last_second->getValue();
242  double time_diff = (latest->header.stamp - last_second->header.stamp).toSec();
243  double velocity = value_diff / time_diff;
244  geometry_msgs::TwistStamped twist;
245  twist.header.frame_id = twist_frame_id_;
246  twist.header.stamp = latest->header.stamp;
247  if (laser_type_ == INFINITE_SPINDLE_HALF || // roll laser
248  laser_type_ == INFINITE_SPINDLE) {
249  twist.twist.angular.x = velocity;
250  }
251  else { // tilt laser
252  twist.twist.angular.y = velocity;
253  }
254  twist_pub_.publish(twist);
255  }
256  }
257 
258  if (use_laser_assembler_) {
259  if (skip_counter_++ % skip_number_ == 0) {
260  laser_assembler::AssembleScans2 srv;
261  srv.request.begin = start;
262  srv.request.end = end;
263  try {
264  if (!not_use_laser_assembler_service_) {
265  if (assemble_cloud_srv_.call(srv)) {
266  sensor_msgs::PointCloud2 output_cloud = srv.response.cloud;
267  output_cloud.header.stamp = stamp;
268  cloud_pub_.publish(output_cloud);
269  }
270  else {
271  NODELET_ERROR("Failed to call assemble cloud service");
272  }
273  }
274  else {
275  // Assemble cloud from local buffer
276  std::vector<sensor_msgs::PointCloud2::ConstPtr> target_clouds;
277  {
278  boost::mutex::scoped_lock lock(cloud_mutex_);
279  if (cloud_buffer_.size() == 0) {
280  return;
281  }
282  for (size_t i = 0; i < cloud_buffer_.size(); i++) {
283  ros::Time the_stamp = cloud_buffer_[i]->header.stamp;
284  if (the_stamp > start && the_stamp < end) {
285  target_clouds.push_back(cloud_buffer_[i]);
286  }
287  }
288  if (clear_assembled_scans_) {
289  cloud_buffer_.removeBefore(end);
290  }
291  else {
292  cloud_buffer_.removeBefore(start);
293  }
294  }
295  sensor_msgs::PointCloud2 output_cloud;
296  getPointCloudFromLocalBuffer(target_clouds, output_cloud);
297  output_cloud.header.stamp = stamp;
298  cloud_pub_.publish(output_cloud);
299  }
300  }
301  catch (...) {
302  NODELET_ERROR("Exception in calling assemble cloud service");
303  }
304  }
305  }
306  }
307 
309  const ros::Time& stamp, const double& joint_angle)
310  {
311  double velocity = joint_angle - prev_angle_;
312  if (velocity > 0 && prev_velocity_ <= 0) {
313  start_time_ = stamp;
314  }
315  else if (velocity < 0 && prev_velocity_ >= 0) {
316  publishTimeRange(stamp, start_time_, stamp);
317  }
318  prev_angle_ = joint_angle;
319  prev_velocity_ = velocity;
320  }
321 
323  const ros::Time& stamp, const double& joint_angle)
324  {
325  double velocity = joint_angle - prev_angle_;
326  if (velocity < 0 && prev_velocity_ >= 0) {
327  start_time_ = stamp;
328  }
329  else if (velocity > 0 && prev_velocity_ <= 0) {
330  publishTimeRange(stamp, start_time_, stamp);
331  }
332  prev_angle_ = joint_angle;
333  prev_velocity_ = velocity;
334  }
335 
337  const ros::Time& stamp, const double& joint_angle)
338  {
339 
340  if (buffer_.size() > 3) {
341  double direction = buffer_[buffer_.size() - 1]->getValue() - joint_angle;
342  int change_count = 0;
343  for (size_t i = buffer_.size() - 1; i > 0; i--) {
344  double current_direction = buffer_[i-1]->getValue() - buffer_[i]->getValue();
345  if (direction * current_direction < 0) {
346  ++change_count;
347  }
348  if (change_count == 2) {
349  ros::Time start_time = buffer_[i]->header.stamp;
350  publishTimeRange(stamp, start_time, stamp);
351  if (clear_assembled_scans_) {
352  buffer_.removeBefore(stamp);
353  }
354  else {
355  buffer_.removeBefore(buffer_[i-1]->header.stamp);
356  }
357  break;
358  }
359  direction = current_direction;
360  }
361  }
362  std_msgs::Header header;
363  header.stamp = stamp;
364  StampedJointAngle::Ptr j(new StampedJointAngle(header, joint_angle));
365  if (buffer_.size() > 0 && buffer_[buffer_.size() - 1]->getValue() == joint_angle) {
366  // do nothing, duplicate value
367  }
368  else {
369  buffer_.push_back(j);
370  }
371  }
372 
374  const ros::Time& stamp, const double& joint_angle, const double& velocity,
375  const double& threshold)
376  {
377  if (velocity == 0) {
378  return;
379  }
380  if (buffer_.size() > 3) {
381  bool jumped = false;
382  for (size_t i = buffer_.size() - 1; i > 0; i--) {
383  // find jump first
384  if (!jumped) {
385  double direction = fmod(buffer_[i-1]->getValue(), 2.0 * M_PI) - fmod(buffer_[i]->getValue(), 2.0 * M_PI);
386  if (direction * velocity > 0) {
387  jumped = true;
388  }
389  }
390  else { // already jumped
391  if (velocity > 0) {
392  if (fmod(buffer_[i-1]->getValue(), 2.0 * M_PI) < fmod(threshold - overwrap_angle_, 2.0 * M_PI)) {
393  publishTimeRange(stamp, buffer_[i-1]->header.stamp, stamp);
394  if (clear_assembled_scans_) {
395  buffer_.removeBefore(stamp);
396  }
397  else {
398  buffer_.removeBefore(buffer_[i-1]->header.stamp);
399  }
400  break;
401  }
402  }
403  else if (velocity < 0) {
404  if (fmod(buffer_[i-1]->getValue(), 2.0 * M_PI) > fmod(threshold + overwrap_angle_, 2.0 * M_PI)) {
405  publishTimeRange(stamp, buffer_[i-1]->header.stamp, stamp);
406  if (clear_assembled_scans_) {
407  buffer_.removeBefore(stamp);
408  }
409  else {
410  buffer_.removeBefore(buffer_[i-1]->header.stamp);
411  }
412  break;
413  }
414  }
415  }
416  //if (buffer_[i]->getValue()
417  }
418  }
419  std_msgs::Header header;
420  header.stamp = stamp;
421  StampedJointAngle::Ptr j(new StampedJointAngle(header, joint_angle));
422  buffer_.push_back(j);
423  }
424 
426  const sensor_msgs::JointState::ConstPtr& msg)
427  {
428  boost::mutex::scoped_lock lock(mutex_);
429  for (size_t i = 0; i < msg->name.size(); i++) {
430  std::string name = msg->name[i];
431  if (name == joint_name_) {
432  vital_checker_->poke();
433  if(msg->position.size() <= i) {
434  ROS_WARN("size of position (%zu) is smaller than joint(%s) position(%zu)",
435  msg->position.size(), name.c_str(), i);
436  return;
437  }
438  if (laser_type_ == TILT_HALF_UP) {
439  processTiltHalfUp(msg->header.stamp, msg->position[i]);
440  }
441  else if (laser_type_ == TILT_HALF_DOWN) {
442  processTiltHalfDown(msg->header.stamp, msg->position[i]);
443  }
444  else if (laser_type_ == TILT) {
445  processTilt(msg->header.stamp, msg->position[i]);
446  }
447  else if (laser_type_ == INFINITE_SPINDLE) {
448  if(msg->velocity.size() <= i) {
449  ROS_WARN("size of velocity (%zu) is smaller than joint(%s) position(%zu)",
450  msg->velocity.size(), name.c_str(), i);
451  return;
452  }
453  processInfiniteSpindle(msg->header.stamp,
454  msg->position[i],
455  msg->velocity[i],
456  msg->position[i]);
457  }
458  else if (laser_type_ == INFINITE_SPINDLE_HALF) {
459  if(msg->velocity.size() <= i) {
460  ROS_WARN("size of velocity (%zu) is smaller than joint(%s) position(%zu)",
461  msg->velocity.size(), name.c_str(), i);
462  return;
463  }
464  processInfiniteSpindle(msg->header.stamp,
465  fmod(msg->position[i], M_PI),
466  msg->velocity[i],
467  fmod(msg->position[i], M_PI));
468  }
469  break;
470  }
471  }
472  }
473 }
474 
#define NODELET_ERROR(...)
virtual void processTiltHalfDown(const ros::Time &stamp, const double &value)
virtual void publishTimeRange(const ros::Time &stamp, const ros::Time &start, const ros::Time &end)
#define NODELET_WARN(...)
virtual void cloudCallback(const sensor_msgs::PointCloud2::ConstPtr &msg)
StampedJointAngle(const std_msgs::Header &header_arg, const double &value)
void summary(unsigned char lvl, const std::string s)
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros::TiltLaserListener, nodelet::Nodelet)
virtual void processInfiniteSpindle(const ros::Time &stamp, const double &joint_angle, const double &velocity, const double &threshold)
std::string getName(void *handle)
#define ROS_WARN(...)
virtual void updateDiagnostic(diagnostic_updater::DiagnosticStatusWrapper &stat)
virtual void jointCallback(const sensor_msgs::JointState::ConstPtr &msg)
#define M_PI
virtual void getPointCloudFromLocalBuffer(const std::vector< sensor_msgs::PointCloud2::ConstPtr > &target_clouds, sensor_msgs::PointCloud2 &output_cloud)
srv
virtual void processTiltHalfUp(const ros::Time &stamp, const double &value)
virtual void processTilt(const ros::Time &stamp, const double &value)
void addDiagnosticErrorSummary(const std::string &string_prefix, jsk_topic_tools::VitalChecker::Ptr vital_checker, diagnostic_updater::DiagnosticStatusWrapper &stat)
virtual void timerCallback(const ros::TimerEvent &e)
static Time now()
void add(const std::string &key, const T &val)
boost::mutex mutex_
virtual bool clearCacheCallback(std_srvs::Empty::Request &req, std_srvs::Empty::Response &res)


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Mon May 3 2021 03:03:47