Public Member Functions | |
ASyncSub (ros::NodeHandle &nh, const std::string &topic, const std::size_t queue_size, callback_t user_callback=0) | |
void | Deactivate () |
void | DeactivateIfOlderThan (const double seconds) |
const ros::Duration | GetFreshness () const |
const ros::Time | GetLastUpdated () const |
const boost::shared_ptr< T const > & | GetMsgConstPtr () const |
T | GetMsgCopy () const |
bool | IsActive () const |
const boost::shared_ptr< T const > & | operator() () const |
Private Types | |
typedef boost::function< void(const boost::shared_ptr< T const > &data)> | callback_t |
Private Member Functions | |
void | cb (const boost::shared_ptr< T const > &msg_cptr) |
Private Attributes | |
bool | active_ |
ros::Time | last_updated_ |
boost::shared_ptr< T const > | msg_cptr_ |
boost::mutex | mutex_ |
ros::NodeHandle | nh |
std::size_t | queue_size_ |
ros::Subscriber | sub_ |
std::string | topic_ |
callback_t | user_callback_ |
Definition at line 73 of file bebop_itl_test.cpp.
typedef boost::function<void (const boost::shared_ptr<T const>& data)> bebop_driver::util::ASyncSub< T >::callback_t [private] |
Definition at line 76 of file bebop_itl_test.cpp.
bebop_driver::util::ASyncSub< T >::ASyncSub | ( | ros::NodeHandle & | nh, |
const std::string & | topic, | ||
const std::size_t | queue_size, | ||
callback_t | user_callback = 0 |
||
) | [inline] |
Definition at line 98 of file bebop_itl_test.cpp.
void bebop_driver::util::ASyncSub< T >::cb | ( | const boost::shared_ptr< T const > & | msg_cptr | ) | [inline, private] |
Definition at line 88 of file bebop_itl_test.cpp.
void bebop_driver::util::ASyncSub< T >::Deactivate | ( | ) | [inline] |
Definition at line 127 of file bebop_itl_test.cpp.
void bebop_driver::util::ASyncSub< T >::DeactivateIfOlderThan | ( | const double | seconds | ) | [inline] |
Definition at line 133 of file bebop_itl_test.cpp.
const ros::Duration bebop_driver::util::ASyncSub< T >::GetFreshness | ( | ) | const [inline] |
Definition at line 155 of file bebop_itl_test.cpp.
const ros::Time bebop_driver::util::ASyncSub< T >::GetLastUpdated | ( | ) | const [inline] |
Definition at line 149 of file bebop_itl_test.cpp.
const boost::shared_ptr<T const>& bebop_driver::util::ASyncSub< T >::GetMsgConstPtr | ( | ) | const [inline] |
Definition at line 113 of file bebop_itl_test.cpp.
T bebop_driver::util::ASyncSub< T >::GetMsgCopy | ( | ) | const [inline] |
Definition at line 107 of file bebop_itl_test.cpp.
bool bebop_driver::util::ASyncSub< T >::IsActive | ( | ) | const [inline] |
Definition at line 143 of file bebop_itl_test.cpp.
const boost::shared_ptr<T const>& bebop_driver::util::ASyncSub< T >::operator() | ( | ) | const [inline] |
Definition at line 121 of file bebop_itl_test.cpp.
bool bebop_driver::util::ASyncSub< T >::active_ [private] |
Definition at line 79 of file bebop_itl_test.cpp.
ros::Time bebop_driver::util::ASyncSub< T >::last_updated_ [private] |
Definition at line 80 of file bebop_itl_test.cpp.
boost::shared_ptr<T const> bebop_driver::util::ASyncSub< T >::msg_cptr_ [private] |
Definition at line 85 of file bebop_itl_test.cpp.
boost::mutex bebop_driver::util::ASyncSub< T >::mutex_ [mutable, private] |
Definition at line 86 of file bebop_itl_test.cpp.
ros::NodeHandle bebop_driver::util::ASyncSub< T >::nh [private] |
Definition at line 78 of file bebop_itl_test.cpp.
std::size_t bebop_driver::util::ASyncSub< T >::queue_size_ [private] |
Definition at line 82 of file bebop_itl_test.cpp.
ros::Subscriber bebop_driver::util::ASyncSub< T >::sub_ [private] |
Definition at line 84 of file bebop_itl_test.cpp.
std::string bebop_driver::util::ASyncSub< T >::topic_ [private] |
Definition at line 81 of file bebop_itl_test.cpp.
callback_t bebop_driver::util::ASyncSub< T >::user_callback_ [private] |
Definition at line 83 of file bebop_itl_test.cpp.