29 #ifndef SWRI_ROSCPP_SUBSCRIBER_IMPL_H_ 30 #define SWRI_ROSCPP_SUBSCRIBER_IMPL_H_ 32 #include <std_msgs/Header.h> 72 if (stamp >= last_header_stamp_) {
77 if (message_count_ == 1) {
78 min_latency_ = latency;
79 max_latency_ = latency;
80 total_latency_ = latency;
82 min_latency_ = std::min(min_latency_, latency);
83 max_latency_ = std::max(max_latency_, latency);
84 double latency_weight_ = 0.1;
85 total_latency_.
fromSec(latency_weight_*latency.
toSec() + (1-latency_weight_)*total_latency_.
toSec());
89 if (message_count_ > 1) {
91 if (message_count_ == 2) {
94 total_periods_ = period;
95 }
else if (message_count_ > 2) {
96 min_period_ = std::min(min_period_, period);
97 max_period_ = std::max(max_period_, period);
98 total_periods_ += period;
105 last_receive_time_ = now;
106 last_header_stamp_ = stamp;
111 if (blocking_timeout_) {
119 if (message_count_ == 0) {
123 if (
age(now) > timeout_) {
132 unmapped_topic_(
"N/A"),
133 mapped_topic_(
"N/A"),
138 blocking_timeout_(false)
172 if (message_count_ < 1) {
174 }
else if (last_header_stamp_.
isValid()) {
185 if (message_count_ < 1) {
194 if (message_count_ < 1) {
203 if (message_count_ < 1) {
212 if (message_count_ < 2) {
221 if (message_count_ < 2) {
230 if (message_count_ < 2) {
239 if (message_count_ < 2) {
259 blocking_timeout_ = block;
292 static const bool value =
true;
295 template<
class M ,
class T>
304 const std::string &topic,
316 ROS_INFO(
"Subscribing to '%s' at '%s'.",
325 &TypedSubscriberImpl::handleMessage<M>,
332 typename boost::enable_if< ros::message_traits::HasHeader<M2>,
void>::type
336 (obj_->*callback_)(msg);
341 typename boost::disable_if< ros::message_traits::HasHeader<M2>,
void>::type
345 (obj_->*callback_)(msg);
352 boost::function<void(const boost::shared_ptr< M const> &)> callback_;
358 const std::string &topic,
369 ROS_INFO(
"Subscribing to '%s' at '%s'.",
374 callback_ = callback;
377 &BindSubscriberImpl::handleMessage<M>,
384 typename boost::enable_if< ros::message_traits::HasHeader<M2>,
void>::type
393 typename boost::disable_if< ros::message_traits::HasHeader<M2>,
void>::type
409 const std::string &topic,
419 ROS_INFO(
"Subscribing to '%s' at '%s'.",
427 &StorageSubscriberImpl::handleMessage<M>,
434 typename boost::enable_if< ros::message_traits::HasHeader<M2>,
void>::type
443 typename boost::disable_if< ros::message_traits::HasHeader<M2>,
void>::type
451 #endif // SWRI_ROSCPP_SUBSCRIBER_IMPL_H_
boost::shared_ptr< M const > * dest_
int numPublishers() const
ros::Duration total_periods_
ros::Duration max_latency_
ros::Duration meanPeriod() const
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
std::string resolveName(const std::string &name, bool remap=true) const
boost::enable_if< ros::message_traits::HasHeader< M2 >, void >::type handleMessage(const boost::shared_ptr< M const > &msg)
ros::Duration minPeriod() const
TypedSubscriberImpl(ros::NodeHandle &nh, const std::string &topic, uint32_t queue_size, void(T::*fp)(const boost::shared_ptr< M const > &), T *obj, const ros::TransportHints &transport_hints)
boost::disable_if< ros::message_traits::HasHeader< M2 >, void >::type handleMessage(const boost::shared_ptr< M const > &msg)
double meanFrequencyHz() const
ros::Duration min_period_
StorageSubscriberImpl(ros::NodeHandle &nh, const std::string &topic, boost::shared_ptr< M const > *dest, const ros::TransportHints &transport_hints)
bool timeoutEnabled() const
ros::Duration meanLatency() const
BindSubscriberImpl(ros::NodeHandle &nh, const std::string &topic, uint32_t queue_size, const boost::function< void(const boost::shared_ptr< M const > &)> &callback, const ros::TransportHints &transport_hints)
const std::string & mappedTopic() const
ros::Duration min_latency_
void processHeader(const ros::Time &stamp)
void setTimeout(const ros::Duration &time_out)
ros::Duration maxLatency() const
boost::disable_if< ros::message_traits::HasHeader< M2 >, void >::type handleMessage(const boost::shared_ptr< M const > &msg)
boost::enable_if< ros::message_traits::HasHeader< M2 >, void >::type handleMessage(const boost::shared_ptr< M const > &msg)
boost::enable_if< ros::message_traits::HasHeader< M2 >, void >::type handleMessage(const boost::shared_ptr< M const > &msg)
ros::Duration age(const ros::Time &now) const
Duration & fromSec(double t)
bool blockTimeouts(bool block)
std::string mapped_topic_
std::string unmapped_topic_
uint32_t getNumPublishers() const
const std::string & unmappedTopic() const
boost::disable_if< ros::message_traits::HasHeader< M2 >, void >::type handleMessage(const boost::shared_ptr< M const > &msg)
void checkTimeout(const ros::Time &now)
ros::Duration minLatency() const
ros::Time last_receive_time_
ros::Time last_header_stamp_
ros::Duration timeout() const
bool timeoutsBlocked() const
ros::Duration max_period_
ROSTIME_DECL const Duration DURATION_MAX
ros::Duration maxPeriod() const
ros::Duration total_latency_