Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036 #include "jsk_pcl_ros/joint_state_static_filter.h"
00037 #include <jsk_topic_tools/rosparam_utils.h>
00038 #include <jsk_recognition_utils/pcl_util.h>
00039
00040 namespace jsk_pcl_ros
00041 {
00042 void JointStateStaticFilter::onInit()
00043 {
00044 DiagnosticNodelet::onInit();
00045
00046 double vital_rate;
00047 pnh_->param("vital_rate", vital_rate, 1.0);
00048 joint_vital_.reset(
00049 new jsk_topic_tools::VitalChecker(1 / vital_rate));
00050 if (!jsk_topic_tools::readVectorParameter(*pnh_,
00051 "joint_names",
00052 joint_names_) ||
00053 joint_names_.size() == 0) {
00054 NODELET_FATAL("NO ~joint_names is specified");
00055 return;
00056 }
00057 pub_ = advertise<sensor_msgs::PointCloud2>(*pnh_, "output", 1);
00058
00059 onInitPostProcess();
00060 }
00061
00062 void JointStateStaticFilter::subscribe()
00063 {
00064 sub_joint_ = pnh_->subscribe("input_joint_state", 1,
00065 &JointStateStaticFilter::jointStateCallback,
00066 this);
00067 sub_input_ = pnh_->subscribe("input", 1,
00068 &JointStateStaticFilter::filter,
00069 this);
00070 }
00071
00072 void JointStateStaticFilter::unsubscribe()
00073 {
00074 sub_joint_.shutdown();
00075 sub_input_.shutdown();
00076 }
00077
00078 void JointStateStaticFilter::filter(
00079 const sensor_msgs::PointCloud2::ConstPtr& msg)
00080 {
00081 boost::mutex::scoped_lock lock(mutex_);
00082 NODELET_DEBUG("Pointcloud Callback");
00083 vital_checker_->poke();
00084 if (isStatic(msg->header.stamp)) {
00085 ROS_DEBUG("static");
00086 pub_.publish(msg);
00087 }
00088 else {
00089 ROS_DEBUG("not static");
00090 }
00091 diagnostic_updater_->update();
00092 }
00093
00094 std::vector<double>
00095 JointStateStaticFilter::filterJointState(
00096 const sensor_msgs::JointState::ConstPtr& msg)
00097 {
00098 std::vector<double> ret;
00099 for (size_t i = 0; i < joint_names_.size(); i++) {
00100 std::string target_joint = joint_names_[i];
00101
00102 bool find_joint = false;
00103 for (size_t j = 0; j < msg->name.size(); j++) {
00104 if (target_joint == msg->name[j]) {
00105 ret.push_back(msg->position[j]);
00106 find_joint = true;
00107 break;
00108 }
00109 }
00110 if (!find_joint) {
00111 return std::vector<double>();
00112 }
00113 }
00114 return ret;
00115 }
00116
00117 bool JointStateStaticFilter::isStatic(
00118 const ros::Time& stamp)
00119 {
00120 double min_diff = DBL_MAX;
00121 bool min_value = false;
00122 for (boost::circular_buffer<StampedBool>::iterator it = buf_.begin();
00123 it != buf_.end();
00124 ++it) {
00125 double diff = fabs((it->get<0>() - stamp).toSec());
00126 if (diff < min_diff) {
00127 min_value = it->get<1>();
00128 min_diff = diff;
00129 }
00130 }
00131 NODELET_DEBUG("min_diff: %f", min_diff);
00132 return min_value;
00133 }
00134
00135 void JointStateStaticFilter::jointStateCallback(
00136 const sensor_msgs::JointState::ConstPtr& msg)
00137 {
00138 boost::mutex::scoped_lock lock(mutex_);
00139 NODELET_DEBUG("jointCallback");
00140
00141 std::vector<double> joints = filterJointState(msg);
00142 if (joints.size() == 0) {
00143 NODELET_DEBUG("cannot find the joints from the input message");
00144 return;
00145 }
00146 joint_vital_->poke();
00147
00148
00149 if (previous_joints_.size() > 0) {
00150
00151 for (size_t i = 0; i < previous_joints_.size(); i++) {
00152
00153
00154 if (fabs(previous_joints_[i] - joints[i]) > eps_) {
00155 buf_.push_front(boost::make_tuple<ros::Time, bool>(
00156 msg->header.stamp, false));
00157 previous_joints_ = joints;
00158 return;
00159 }
00160 }
00161 buf_.push_front(boost::make_tuple<ros::Time, bool>(
00162 msg->header.stamp, true));
00163 }
00164 previous_joints_ = joints;
00165 }
00166
00167 void JointStateStaticFilter::updateDiagnostic(
00168 diagnostic_updater::DiagnosticStatusWrapper &stat)
00169 {
00170 if (vital_checker_->isAlive()) {
00171 if (joint_vital_->isAlive()) {
00172 stat.summary(diagnostic_msgs::DiagnosticStatus::OK,
00173 name_ + " running");
00174 }
00175 else {
00176 jsk_recognition_utils::addDiagnosticErrorSummary(
00177 name_, joint_vital_, stat);
00178 }
00179 }
00180 else {
00181 jsk_recognition_utils::addDiagnosticErrorSummary(
00182 name_, vital_checker_, stat);
00183 }
00184
00185 }
00186 }
00187
00188 #include <pluginlib/class_list_macros.h>
00189 PLUGINLIB_EXPORT_CLASS (jsk_pcl_ros::JointStateStaticFilter, nodelet::Nodelet);