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 total_latency_ += latency;
88 if (message_count_ > 1) {
90 if (message_count_ == 2) {
93 total_periods_ = period;
94 }
else if (message_count_ > 2) {
95 min_period_ = std::min(min_period_, period);
96 max_period_ = std::max(max_period_, period);
97 total_periods_ += period;
104 last_receive_time_ = now;
105 last_header_stamp_ = stamp;
110 if (blocking_timeout_) {
118 if (message_count_ == 0) {
122 if (
age(now) > timeout_) {
131 unmapped_topic_(
"N/A"),
132 mapped_topic_(
"N/A"),
137 blocking_timeout_(false)
171 if (message_count_ < 1) {
173 }
else if (last_header_stamp_.
isValid()) {
184 if (message_count_ < 1) {
193 if (message_count_ < 1) {
202 if (message_count_ < 1) {
211 if (message_count_ < 2) {
220 if (message_count_ < 2) {
229 if (message_count_ < 2) {
238 if (message_count_ < 2) {
258 blocking_timeout_ = block;
291 static const bool value =
true;
294 template<
class M ,
class T>
303 const std::string &topic,
315 ROS_INFO(
"Subscribing to '%s' at '%s'.",
324 &TypedSubscriberImpl::handleMessage<M>,
331 typename boost::enable_if< ros::message_traits::HasHeader<M2>,
void>::type
335 (obj_->*callback_)(msg);
340 typename boost::disable_if< ros::message_traits::HasHeader<M2>,
void>::type
344 (obj_->*callback_)(msg);
351 boost::function<void(const boost::shared_ptr< M const> &)> callback_;
357 const std::string &topic,
368 ROS_INFO(
"Subscribing to '%s' at '%s'.",
373 callback_ = callback;
376 &BindSubscriberImpl::handleMessage<M>,
383 typename boost::enable_if< ros::message_traits::HasHeader<M2>,
void>::type
392 typename boost::disable_if< ros::message_traits::HasHeader<M2>,
void>::type
408 const std::string &topic,
418 ROS_INFO(
"Subscribing to '%s' at '%s'.",
426 &StorageSubscriberImpl::handleMessage<M>,
433 typename boost::enable_if< ros::message_traits::HasHeader<M2>,
void>::type
442 typename boost::disable_if< ros::message_traits::HasHeader<M2>,
void>::type
450 #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
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_