44 DiagnosticNodelet::onInit();
47 pnh_->param(
"vital_rate", vital_rate, 1.0);
57 pub_ = advertise<sensor_msgs::PointCloud2>(*
pnh_,
"output", 1);
79 const sensor_msgs::PointCloud2::ConstPtr&
msg)
96 const sensor_msgs::JointState::ConstPtr&
msg)
98 std::vector<double> ret;
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]);
111 return std::vector<double>();
120 double min_diff = DBL_MAX;
121 bool min_value =
false;
122 for (boost::circular_buffer<StampedBool>::iterator it =
buf_.begin();
125 double diff = fabs((it->get<0>() - stamp).toSec());
126 if (diff < min_diff) {
127 min_value = it->get<1>();
136 const sensor_msgs::JointState::ConstPtr&
msg)
142 if (joints.size() == 0) {
143 NODELET_DEBUG(
"cannot find the joints from the input message");
155 buf_.push_front(boost::make_tuple<ros::Time, bool>(
156 msg->header.stamp,
false));
161 buf_.push_front(boost::make_tuple<ros::Time, bool>(
162 msg->header.stamp,
true));
172 stat.
summary(diagnostic_msgs::DiagnosticStatus::OK,
virtual void filter(const sensor_msgs::PointCloud2::ConstPtr &msg)
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_
std::vector< double > previous_joints_
virtual bool isStatic(const ros::Time &stamp)
virtual void unsubscribe()
ros::Subscriber sub_input_
virtual std::vector< double > filterJointState(const sensor_msgs::JointState::ConstPtr &msg)
virtual void updateDiagnostic(diagnostic_updater::DiagnosticStatusWrapper &stat)
std::vector< std::string > joint_names_
ros::Subscriber sub_joint_
#define NODELET_FATAL(...)
boost::circular_buffer< StampedBool > buf_
#define NODELET_DEBUG(...)
PLUGINLIB_EXPORT_CLASS(jsk_pcl_ros::JointStateStaticFilter, nodelet::Nodelet)