Go to the documentation of this file.
29 #ifndef SWRI_ROSCPP_SUBSCRIBER_IMPL_H_
30 #define SWRI_ROSCPP_SUBSCRIBER_IMPL_H_
32 #include <std_msgs/Header.h>
85 double latency_weight_ = 0.1;
300 template<
class M ,
class T>
309 const std::string &topic,
321 ROS_INFO(
"Subscribing to '%s' at '%s'.",
330 &TypedSubscriberImpl::handleMessage<M>,
337 typename boost::enable_if< ros::message_traits::HasHeader<M2>,
void>::type
346 typename boost::disable_if< ros::message_traits::HasHeader<M2>,
void>::type
363 const std::string &topic,
374 ROS_INFO(
"Subscribing to '%s' at '%s'.",
382 &BindSubscriberImpl::handleMessage<M>,
389 typename boost::enable_if< ros::message_traits::HasHeader<M2>,
void>::type
398 typename boost::disable_if< ros::message_traits::HasHeader<M2>,
void>::type
414 const std::string &topic,
424 ROS_INFO(
"Subscribing to '%s' at '%s'.",
432 &StorageSubscriberImpl::handleMessage<M>,
439 typename boost::enable_if< ros::message_traits::HasHeader<M2>,
void>::type
448 typename boost::disable_if< ros::message_traits::HasHeader<M2>,
void>::type
456 #endif // SWRI_ROSCPP_SUBSCRIBER_IMPL_H_
Duration & fromSec(double t)
virtual ~SubscriberImpl()
ros::Time last_header_stamp_
ros::Duration min_latency_
void processHeader(const ros::Time &stamp)
ros::Duration max_period_
std::string mapped_topic_
boost::disable_if< ros::message_traits::HasHeader< M2 >, void >::type handleMessage(const boost::shared_ptr< M const > &msg)
ros::Duration maxPeriod() const
bool blockTimeouts(bool block)
ros::Duration minLatency() const
const ROSTIME_DECL Duration DURATION_MAX
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)
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)
uint32_t getNumPublishers() const
ros::Duration total_periods_
ros::Duration timeout() const
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)
void checkTimeout(const ros::Time &now)
ros::Duration age(const ros::Time &now) const
ros::Duration minPeriod() const
boost::function< void(const boost::shared_ptr< M const > &)> callback_
ros::Duration meanPeriod() const
ros::Duration maxLatency() const
const std::string & unmappedTopic() const
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
ros::Duration total_latency_
boost::enable_if< ros::message_traits::HasHeader< M2 >, void >::type handleMessage(const boost::shared_ptr< M const > &msg)
ros::Duration min_period_
boost::disable_if< ros::message_traits::HasHeader< M2 >, void >::type handleMessage(const boost::shared_ptr< M const > &msg)
void setTimeout(const ros::Duration &time_out)
ros::Duration max_latency_
bool timeoutEnabled() const
std::string unmapped_topic_
void(T::* callback_)(const boost::shared_ptr< M const > &)
const std::string & mappedTopic() const
boost::enable_if< ros::message_traits::HasHeader< M2 >, void >::type handleMessage(const boost::shared_ptr< M const > &msg)
boost::shared_ptr< M const > * dest_
ros::Duration meanLatency() const
double meanFrequencyHz() const
int numPublishers() const
boost::disable_if< ros::message_traits::HasHeader< M2 >, void >::type handleMessage(const boost::shared_ptr< M const > &msg)
StorageSubscriberImpl(ros::NodeHandle &nh, const std::string &topic, boost::shared_ptr< M const > *dest, const ros::TransportHints &transport_hints)
bool timeoutsBlocked() const
ros::Time last_receive_time_
swri_roscpp
Author(s): P. J. Reed
autogenerated on Fri Aug 2 2024 08:39:15