joint_state_static_filter_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 
39 
40 namespace jsk_pcl_ros
41 {
43  {
44  DiagnosticNodelet::onInit();
45 
46  double vital_rate;
47  pnh_->param("vital_rate", vital_rate, 1.0);
48  joint_vital_.reset(
49  new jsk_topic_tools::VitalChecker(1 / vital_rate));
51  "joint_names",
52  joint_names_) ||
53  joint_names_.size() == 0) {
54  NODELET_FATAL("NO ~joint_names is specified");
55  return;
56  }
57  pub_ = advertise<sensor_msgs::PointCloud2>(*pnh_, "output", 1);
58 
60  }
61 
63  {
64  sub_joint_ = pnh_->subscribe("input_joint_state", 1,
66  this);
67  sub_input_ = pnh_->subscribe("input", 1,
69  this);
70  }
71 
73  {
76  }
77 
79  const sensor_msgs::PointCloud2::ConstPtr& msg)
80  {
81  boost::mutex::scoped_lock lock(mutex_);
82  NODELET_DEBUG("Pointcloud Callback");
83  vital_checker_->poke();
84  if (isStatic(msg->header.stamp)) {
85  ROS_DEBUG("static");
86  pub_.publish(msg);
87  }
88  else {
89  ROS_DEBUG("not static");
90  }
91  diagnostic_updater_->update();
92  }
93 
94  std::vector<double>
96  const sensor_msgs::JointState::ConstPtr& msg)
97  {
98  std::vector<double> ret;
99  for (size_t i = 0; i < joint_names_.size(); i++) {
100  std::string target_joint = joint_names_[i];
101  // lookup target_joint from msg
102  bool find_joint = false;
103  for (size_t j = 0; j < msg->name.size(); j++) {
104  if (target_joint == msg->name[j]) {
105  ret.push_back(msg->position[j]);
106  find_joint = true;
107  break;
108  }
109  }
110  if (!find_joint) {
111  return std::vector<double>();
112  }
113  }
114  return ret;
115  }
116 
118  const ros::Time& stamp)
119  {
120  double min_diff = DBL_MAX;
121  bool min_value = false;
122  for (boost::circular_buffer<StampedBool>::iterator it = buf_.begin();
123  it != buf_.end();
124  ++it) {
125  double diff = fabs((it->get<0>() - stamp).toSec());
126  if (diff < min_diff) {
127  min_value = it->get<1>();
128  min_diff = diff;
129  }
130  }
131  NODELET_DEBUG("min_diff: %f", min_diff);
132  return min_value;
133  }
134 
136  const sensor_msgs::JointState::ConstPtr& msg)
137  {
138  boost::mutex::scoped_lock lock(mutex_);
139  NODELET_DEBUG("jointCallback");
140  // filter out joints based on joint names
141  std::vector<double> joints = filterJointState(msg);
142  if (joints.size() == 0) {
143  NODELET_DEBUG("cannot find the joints from the input message");
144  return;
145  }
146  joint_vital_->poke();
147 
148  // check the previous state...
149  if (previous_joints_.size() > 0) {
150  // compute velocity
151  for (size_t i = 0; i < previous_joints_.size(); i++) {
152  // NODELET_INFO("[%s] diff: %f", joint_names_[i].c_str(),
153  // fabs(previous_joints_[i] - joints[i]));
154  if (fabs(previous_joints_[i] - joints[i]) > eps_) {
155  buf_.push_front(boost::make_tuple<ros::Time, bool>(
156  msg->header.stamp, false));
157  previous_joints_ = joints;
158  return;
159  }
160  }
161  buf_.push_front(boost::make_tuple<ros::Time, bool>(
162  msg->header.stamp, true));
163  }
164  previous_joints_ = joints;
165  }
166 
169  {
170  if (vital_checker_->isAlive()) {
171  if (joint_vital_->isAlive()) {
172  stat.summary(diagnostic_msgs::DiagnosticStatus::OK,
173  name_ + " running");
174  }
175  else {
177  name_, joint_vital_, stat, diagnostic_error_level_);
178  }
179  }
180  else {
182  name_, vital_checker_, stat, diagnostic_error_level_);
183  }
184 
185  }
186 }
187 
virtual void filter(const sensor_msgs::PointCloud2::ConstPtr &msg)
TimeredDiagnosticUpdater::Ptr diagnostic_updater_
void publish(const boost::shared_ptr< M > &message) const
void summary(unsigned char lvl, const std::string s)
virtual void jointStateCallback(const sensor_msgs::JointState::ConstPtr &msg)
IMETHOD Vector diff(const Vector &p_w_a, const Vector &p_w_b, double dt=1)
jsk_topic_tools::VitalChecker::Ptr joint_vital_
bool readVectorParameter(ros::NodeHandle &nh, const std::string &param_name, std::vector< double > &result)
boost::shared_ptr< ros::NodeHandle > pnh_
virtual std::vector< double > filterJointState(const sensor_msgs::JointState::ConstPtr &msg)
virtual void updateDiagnostic(diagnostic_updater::DiagnosticStatusWrapper &stat)
jsk_topic_tools::VitalChecker::Ptr vital_checker_
void addDiagnosticErrorSummary(const std::string &string_prefix, jsk_topic_tools::VitalChecker::Ptr vital_checker, diagnostic_updater::DiagnosticStatusWrapper &stat)
#define NODELET_FATAL(...)
boost::circular_buffer< StampedBool > buf_
#define NODELET_DEBUG(...)
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros::JointStateStaticFilter, nodelet::Nodelet)
#define ROS_DEBUG(...)


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